mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Linux_HAL_Essentials: cleanup PWM PRU code
change firmware name to pwmpru1
This commit is contained in:
parent
e438250068
commit
aa1db00908
Binary file not shown.
@ -300,7 +300,7 @@
|
||||
pdbg = <0x24400>;
|
||||
|
||||
firmware-elf;
|
||||
firmware = "testpru1";
|
||||
firmware = "pwmpru1";
|
||||
|
||||
/* NOTE: no resource table, no vrings for this one */
|
||||
};
|
||||
|
@ -5,7 +5,7 @@
|
||||
|
||||
.PHONY: all clean
|
||||
|
||||
all: testpru1.stripped testpru1.lst
|
||||
all: pwmpru1.stripped pwmpru1.lst
|
||||
|
||||
CC=clpru
|
||||
LD=lnkpru
|
||||
@ -30,7 +30,7 @@ LDFLAGS=-cr --diag_warning=225 -llnk-am33xx.cmd -x
|
||||
|
||||
STRIPFLAGS=-p
|
||||
|
||||
OBJS1:=testpru1.obj
|
||||
OBJS1:=pwmpru1.obj
|
||||
|
||||
%.obj: %.c
|
||||
$(CC) $(CFLAGS) -c $< -ea=.s
|
||||
@ -38,18 +38,18 @@ OBJS1:=testpru1.obj
|
||||
%.obj: %.asm
|
||||
$(CC) $(CFLAGS) -c $<
|
||||
|
||||
testpru1: $(OBJS1)
|
||||
pwmpru1: $(OBJS1)
|
||||
$(CC) $(CFLAGS) $^ -q -z $(LDFLAGS) -o $@
|
||||
|
||||
testpru1.stripped: testpru1
|
||||
pwmpru1.stripped: pwmpru1
|
||||
$(STRIP) $(STRIPFLAGS) $< -o $@
|
||||
|
||||
testpru1.lst: testpru1
|
||||
pwmpru1.lst: pwmpru1
|
||||
$(OBJDUMP) -1 $< > $@
|
||||
|
||||
clean:
|
||||
rm -f \
|
||||
testpru1 testpru1.asm \
|
||||
pwmpru1 pwmpru1.asm \
|
||||
*.obj *.lst *.out *.stripped \
|
||||
tags
|
||||
|
@ -21,8 +21,7 @@ struct pwm_config {
|
||||
/* 14, 15 are not routed out for PRU1 */
|
||||
#define PWM_EN_MASK ( \
|
||||
BIT( 0)|BIT( 1)|BIT( 2)|BIT( 3)|BIT( 4)|BIT( 5)|BIT( 6)|BIT( 7)| \
|
||||
BIT( 8)|BIT( 9)|BIT(10)|BIT(11)|BIT(12)|BIT(13) | \
|
||||
BIT(16 + 5) \
|
||||
BIT( 8)|BIT( 9)|BIT(10)|BIT(11)|BIT(12) \
|
||||
)
|
||||
|
||||
#define MIN_PWM_PULSE PRU_us(4)
|
||||
@ -58,6 +57,18 @@ struct pwm_cmd_l{
|
||||
};
|
||||
|
||||
|
||||
struct cxt {
|
||||
u32 cnt;
|
||||
u32 next;
|
||||
u32 enmask;
|
||||
u32 stmask;
|
||||
u32 setmsk;
|
||||
u32 clrmsk;
|
||||
u32 deltamin;
|
||||
u32 *next_hi_lo;
|
||||
};
|
||||
|
||||
|
||||
/* the command is at the start of shared DPRAM */
|
||||
#define PWM_CMD ((volatile struct pwm_cmd *)DPRAM_SHARED)
|
||||
|
@ -4,7 +4,6 @@
|
||||
*/
|
||||
|
||||
#define PRU1
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdarg.h>
|
||||
@ -16,36 +15,6 @@
|
||||
#include "prucomm.h"
|
||||
|
||||
|
||||
extern void delay_cycles(u32 delay);
|
||||
extern void delay_cycles_accurate(u32 delay);
|
||||
extern void delay_cycles_accurate2(u32 delay);
|
||||
extern u32 read_other_r30(void);
|
||||
|
||||
extern void update_gpo(u32 clrmsk, u32 setmsk);
|
||||
|
||||
void pwm_loop(u32 hi, u32 lo)
|
||||
{
|
||||
while (!pru_signal()) {
|
||||
__R30 |= (1 << 13);
|
||||
delay_cycles(hi);
|
||||
__R30 &= ~(1 << 13);
|
||||
delay_cycles(lo);
|
||||
}
|
||||
}
|
||||
|
||||
void pwm_loop2(u32 hi, u32 lo)
|
||||
{
|
||||
while (!pru_signal()) {
|
||||
__R30 |= (1 << 13);
|
||||
delay_cycles_accurate2(hi);
|
||||
__R30 &= ~(1 << 13);
|
||||
delay_cycles_accurate2(lo);
|
||||
}
|
||||
}
|
||||
|
||||
#define T1 asm (" .global T1\nT1:");
|
||||
#define T2 asm (" .global T2\nT2:");
|
||||
|
||||
struct pwm_cmd_l cfg;
|
||||
|
||||
static void pwm_setup(void)
|
||||
@ -55,29 +24,8 @@ static void pwm_setup(void)
|
||||
cfg.enmask = 0;
|
||||
for (i = 0; i < MAX_PWMS; i++)
|
||||
cfg.hilo[i][0] = cfg.hilo[i][1] = PRU_us(200);
|
||||
|
||||
#if 0
|
||||
cfg.enmask = BIT(13) | BIT(12);
|
||||
cfg.hilo[12][0] = PRU_us(333);
|
||||
cfg.hilo[12][1] = PRU_us(333);
|
||||
cfg.hilo[13][0] = PRU_us(100);
|
||||
cfg.hilo[13][1] = PRU_us(100);
|
||||
#endif
|
||||
}
|
||||
|
||||
#undef USE_PWM_LOOP
|
||||
#define USE_PWM_MACRO
|
||||
|
||||
struct cxt {
|
||||
u32 cnt;
|
||||
u32 next;
|
||||
u32 enmask;
|
||||
u32 stmask;
|
||||
u32 setmsk;
|
||||
u32 clrmsk;
|
||||
u32 deltamin;
|
||||
u32 *next_hi_lo;
|
||||
};
|
||||
|
||||
static inline u32 read_PIEP_COUNT(void)
|
||||
{
|
||||
@ -85,70 +33,10 @@ static inline u32 read_PIEP_COUNT(void)
|
||||
|
||||
}
|
||||
|
||||
static void handle_pwm_cmd(struct cxt *cxt)
|
||||
{
|
||||
u8 i;
|
||||
u32 msk, setmsk, clrmsk;
|
||||
u32 enmask, stmask, cnt, deltamin, next;
|
||||
u32 *nextp;
|
||||
u32 *next_hi_lop;
|
||||
const u32 *hilop;
|
||||
cnt = cxt->cnt;
|
||||
next = cxt->next;
|
||||
enmask = cxt->enmask;
|
||||
stmask = cxt->stmask;
|
||||
setmsk = cxt->setmsk;
|
||||
clrmsk = cxt->clrmsk;
|
||||
deltamin = cxt->deltamin;
|
||||
next_hi_lop = cxt->next_hi_lo;
|
||||
|
||||
// sc_printf("cnt=%x next=%x deltamin=%x", cnt, next, deltamin);
|
||||
|
||||
for (i = 0; i < MAX_PWMS; i++){
|
||||
cfg.hilo[i][0] = PWM_CMD->periodhi[i][1];
|
||||
cfg.hilo[i][1] = PWM_CMD->periodhi[i][0] - PWM_CMD->periodhi[i][1];
|
||||
PWM_CMD->hilo_read[i][0] = cfg.hilo[i][0];
|
||||
PWM_CMD->hilo_read[i][1] = cfg.hilo[i][1];
|
||||
}
|
||||
|
||||
cfg.enmask = PWM_CMD->enmask;
|
||||
PWM_CMD->enmask_read = cfg.enmask;
|
||||
enmask = cfg.enmask;
|
||||
stmask = 0; /* starting all low */
|
||||
|
||||
clrmsk = 0;
|
||||
for (i = 0, msk = 1, nextp = next_hi_lop, hilop = &cfg.hilo[0][0];
|
||||
i < MAX_PWMS;
|
||||
i++, msk <<= 1, nextp += 3, hilop += 2) {
|
||||
if ((enmask & msk) == 0) {
|
||||
nextp[1] = PRU_us(100); /* default */
|
||||
nextp[2] = PRU_us(100);
|
||||
continue;
|
||||
}
|
||||
nextp[0] = cnt; /* next */
|
||||
nextp[1] = hilop[0]; /* hi */
|
||||
nextp[2] = hilop[1]; /* lo */
|
||||
}
|
||||
|
||||
clrmsk = enmask;
|
||||
setmsk = 0;
|
||||
/* guaranteed to be immediate */
|
||||
deltamin = 0;
|
||||
|
||||
cxt->cnt = cnt;
|
||||
cxt->next = next;
|
||||
cxt->enmask = enmask;
|
||||
cxt->stmask = stmask;
|
||||
cxt->setmsk = setmsk;
|
||||
cxt->clrmsk = clrmsk;
|
||||
cxt->deltamin = deltamin;
|
||||
}
|
||||
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
u8 i;
|
||||
u32 cnt, next, magic;
|
||||
u32 cnt, next;
|
||||
u32 msk, setmsk, clrmsk;
|
||||
u32 delta, deltamin, tnext, hi, lo;
|
||||
u32 *nextp;
|
||||
@ -164,11 +52,7 @@ int main(int argc, char *argv[])
|
||||
SYSCFG_IDLE_MODE_NO | SYSCFG_STANDBY_MODE_NO;
|
||||
|
||||
/* our PRU wins arbitration */
|
||||
#if defined(PRU0)
|
||||
PRUCFG_SPP &= ~SPP_PRU1_PAD_HP_EN;
|
||||
#elif defined(PRU1)
|
||||
PRUCFG_SPP |= SPP_PRU1_PAD_HP_EN;
|
||||
#endif
|
||||
pwm_setup();
|
||||
|
||||
/* configure timer */
|
||||
@ -179,9 +63,6 @@ int main(int argc, char *argv[])
|
||||
PIEP_CMP_CFG |= CMP_CFG_CMP_EN(1);
|
||||
PIEP_GLOBAL_CFG |= GLOBAL_CFG_CNT_ENABLE;
|
||||
|
||||
/* copy from cfg to cxt */
|
||||
|
||||
|
||||
/* initialize */
|
||||
cnt = read_PIEP_COUNT();
|
||||
|
||||
@ -212,25 +93,43 @@ int main(int argc, char *argv[])
|
||||
while(1) {
|
||||
|
||||
/* signalled interrupt from either PRU0 or host */
|
||||
|
||||
if(PWM_CMD->magic == PWM_CMD_MAGIC) {
|
||||
cxt.cnt = cnt;
|
||||
cxt.next = next;
|
||||
cxt.enmask = enmask;
|
||||
cxt.stmask = stmask;
|
||||
cxt.setmsk = setmsk;
|
||||
cxt.clrmsk = clrmsk;
|
||||
cxt.deltamin = deltamin;
|
||||
cxt.next_hi_lo = &next_hi_lo[0][0];
|
||||
clrmsk = enmask;
|
||||
setmsk = 0;
|
||||
/* guaranteed to be immediate */
|
||||
deltamin = 0;
|
||||
|
||||
handle_pwm_cmd(&cxt);
|
||||
for (i = 0; i < MAX_PWMS; i++){
|
||||
cfg.hilo[i][0] = PWM_CMD->periodhi[i][1];
|
||||
cfg.hilo[i][1] = PWM_CMD->periodhi[i][0] - PWM_CMD->periodhi[i][1];
|
||||
PWM_CMD->hilo_read[i][0] = cfg.hilo[i][0];
|
||||
PWM_CMD->hilo_read[i][1] = cfg.hilo[i][1];
|
||||
}
|
||||
|
||||
cfg.enmask = PWM_CMD->enmask;
|
||||
PWM_CMD->enmask_read = cfg.enmask;
|
||||
enmask = cfg.enmask;
|
||||
stmask = 0; /* starting all low */
|
||||
|
||||
clrmsk = 0;
|
||||
for (i = 0, msk = 1, nextp = next_hi_lo, hilop = &cfg.hilo[0][0];
|
||||
i < MAX_PWMS;
|
||||
i++, msk <<= 1, nextp += 3, hilop += 2) {
|
||||
if ((enmask & msk) == 0) {
|
||||
nextp[1] = PRU_us(100); /* default */
|
||||
nextp[2] = PRU_us(100);
|
||||
continue;
|
||||
}
|
||||
nextp[0] = cnt; /* next */
|
||||
nextp[1] = hilop[0]; /* hi */
|
||||
nextp[2] = hilop[1]; /* lo */
|
||||
}
|
||||
clrmsk = enmask;
|
||||
setmsk = 0;
|
||||
/* guaranteed to be immediate */
|
||||
deltamin = 0;
|
||||
|
||||
cnt = cxt.cnt;
|
||||
next = cxt.next;
|
||||
enmask = cxt.enmask;
|
||||
stmask = cxt.stmask;
|
||||
setmsk = cxt.setmsk;
|
||||
clrmsk = cxt.clrmsk;
|
||||
deltamin = cxt.deltamin;
|
||||
PWM_CMD->magic = PWM_REPLY_MAGIC;
|
||||
}
|
||||
PWM_CMD->enmask_read = enmask;
|
||||
@ -271,38 +170,7 @@ int main(int argc, char *argv[])
|
||||
} \
|
||||
} while (0)
|
||||
|
||||
#ifdef USE_PWM_LOOP
|
||||
for (i = 0, msk = 1, nextp = &next_hi_lo[0][0]; i < MAX_PWMS; i++, msk <<= 1, nextp += 3) {
|
||||
|
||||
if ((enmask & msk) == 0)
|
||||
continue;
|
||||
|
||||
tnext = nextp[0];
|
||||
hi = nextp[1];
|
||||
lo = nextp[2];
|
||||
|
||||
/* avoid signed arithmetic */
|
||||
while (((delta = (tnext - cnt)) & (1U << 31)) != 0) {
|
||||
/* toggle the state */
|
||||
if (stmask & msk) {
|
||||
stmask &= ~msk;
|
||||
clrmsk &= ~msk;
|
||||
tnext += lo;
|
||||
} else {
|
||||
stmask |= msk;
|
||||
setmsk |= msk;
|
||||
tnext += hi;
|
||||
}
|
||||
}
|
||||
if (delta <= deltamin) {
|
||||
deltamin = delta;
|
||||
next = tnext;
|
||||
}
|
||||
nextp[0] = tnext;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_PWM_MACRO
|
||||
|
||||
#if MAX_PWMS > 0 && (PWM_EN_MASK & BIT(0))
|
||||
SINGLE_PWM(0);
|
||||
@ -398,8 +266,7 @@ int main(int argc, char *argv[])
|
||||
SINGLE_PWM(30);
|
||||
#endif
|
||||
#if MAX_PWMS > 31 && (PWM_EN_MASK & BIT(31))
|
||||
SINGLE_PWM(30);
|
||||
#endif
|
||||
SINGLE_PWM(31);
|
||||
#endif
|
||||
/* results in set bits where there are changes */
|
||||
delta = ~clrmsk | setmsk;
|
||||
@ -409,12 +276,6 @@ int main(int argc, char *argv[])
|
||||
if ((delta >> 16) != 0)
|
||||
pru_other_and_or_reg(30, (clrmsk >> 16) | 0xffff0000, setmsk >> 16);
|
||||
|
||||
#if 0
|
||||
cnt = read_PIEP_COUNT();
|
||||
if (((next - cnt) & (1U << 31)) == 0 && delta > PRU_ms(1)) {
|
||||
sc_printf("bad next=%x cnt=%x", next, cnt);
|
||||
}
|
||||
#endif
|
||||
/* loop while nothing changes */
|
||||
do {
|
||||
cnt = read_PIEP_COUNT();
|
BIN
Tools/Linux_HAL_Essentials/pwmpru1
Normal file
BIN
Tools/Linux_HAL_Essentials/pwmpru1
Normal file
Binary file not shown.
@ -4,7 +4,7 @@ if [ "`echo $1`" = "load" ]; then
|
||||
cp BB-SPI1-SWP-01-00A0.dtbo /lib/firmware/
|
||||
cp BB-BONE-PRU-05-00A0.dtbo /lib/firmware/
|
||||
cp testpru0 /lib/firmware
|
||||
cp testpru1 /lib/firmware
|
||||
cp pwmpru1 /lib/firmware
|
||||
echo BB-BONE-PRU-05 > /sys/devices/bone_capemgr.*/slots
|
||||
echo BB-SPI0-SWP-01 > /sys/devices/bone_capemgr.*/slots
|
||||
echo BB-SPI1-SWP-01 > /sys/devices/bone_capemgr.*/slots
|
||||
@ -14,8 +14,8 @@ if [ "`echo $1`" = "load" ]; then
|
||||
elif [ "`echo $1`" = "reload" ]; then
|
||||
echo "Loading Firmware..."
|
||||
cp testpru0 /lib/firmware
|
||||
cp testpru1 /lib/firmware
|
||||
echo 0:testpru0,1:testpru1 > /sys/devices/ocp.3/4a300000.prurproc/load
|
||||
cp pwmpru1 /lib/firmware
|
||||
echo 0:testpru0,1:pwmpru1 > /sys/devices/ocp.3/4a300000.prurproc/load
|
||||
else
|
||||
echo "Usage:"
|
||||
echo " ./startup.sh load : to load the capes and firmware"
|
||||
|
Binary file not shown.
Loading…
Reference in New Issue
Block a user