current working PoC
This commit is contained in:
parent
c6db09ac2c
commit
05b07e5ee3
1 changed files with 14 additions and 14 deletions
|
|
@ -62,7 +62,7 @@ extern crate alloc;
|
||||||
//target RPM
|
//target RPM
|
||||||
const DEFAULT_TARGET_RPM: u32 = 4000;
|
const DEFAULT_TARGET_RPM: u32 = 4000;
|
||||||
//in seconds
|
//in seconds
|
||||||
const DEFAULT_SPIN_TIME: u32 = 10;
|
const DEFAULT_SPIN_TIME: u64 = 10;
|
||||||
// This creates a default app-descriptor required by the esp-idf bootloader.
|
// This creates a default app-descriptor required by the esp-idf bootloader.
|
||||||
// For more information see: <https://docs.espressif.com/projects/esp-idf/en/stable/esp32/api-reference/system/app_image_format.html#application-description>
|
// For more information see: <https://docs.espressif.com/projects/esp-idf/en/stable/esp32/api-reference/system/app_image_format.html#application-description>
|
||||||
esp_bootloader_esp_idf::esp_app_desc!();
|
esp_bootloader_esp_idf::esp_app_desc!();
|
||||||
|
|
@ -129,7 +129,7 @@ fn main() -> ! {
|
||||||
let loop_time = Duration::from_micros(10);
|
let loop_time = Duration::from_micros(10);
|
||||||
let cfg = pid::PidConfigBuilder::default()
|
let cfg = pid::PidConfigBuilder::default()
|
||||||
.kp(2.0)
|
.kp(2.0)
|
||||||
.ki(0.0)
|
.ki(0.4)
|
||||||
.output_limits(100.00, 400.00)
|
.output_limits(100.00, 400.00)
|
||||||
.sample_time(loop_time)
|
.sample_time(loop_time)
|
||||||
.filter_tc(0.1)
|
.filter_tc(0.1)
|
||||||
|
|
@ -137,8 +137,6 @@ fn main() -> ! {
|
||||||
.expect("Failed to build a PID configuration");
|
.expect("Failed to build a PID configuration");
|
||||||
let controller = pid::FuncPidController::new(cfg);
|
let controller = pid::FuncPidController::new(cfg);
|
||||||
let mut ctx = PidContext::new(Millis(0), 0.0, 0.0);
|
let mut ctx = PidContext::new(Millis(0), 0.0, 0.0);
|
||||||
let set_point = DEFAULT_TARGET_RPM;
|
|
||||||
let mut rpm = 0;
|
|
||||||
let mut control: f32 = 200.0;
|
let mut control: f32 = 200.0;
|
||||||
let mut timg0 = TimerGroup::new(peripherals.TIMG0);
|
let mut timg0 = TimerGroup::new(peripherals.TIMG0);
|
||||||
let coat_timer = timg0.timer0;
|
let coat_timer = timg0.timer0;
|
||||||
|
|
@ -177,8 +175,8 @@ fn main() -> ! {
|
||||||
let mut display = Nextion::new(&mut uart0);
|
let mut display = Nextion::new(&mut uart0);
|
||||||
//we just set it to page0 to be sure
|
//we just set it to page0 to be sure
|
||||||
display.send_command(b"page page0");
|
display.send_command(b"page page0");
|
||||||
let mut _rpm = DEFAULT_TARGET_RPM;
|
let mut target_rpm = DEFAULT_TARGET_RPM;
|
||||||
let mut _timer = DEFAULT_SPIN_TIME;
|
let mut timer:u64 = DEFAULT_SPIN_TIME;
|
||||||
let mut started = false;
|
let mut started = false;
|
||||||
loop {
|
loop {
|
||||||
if display.read_ready() {
|
if display.read_ready() {
|
||||||
|
|
@ -198,11 +196,11 @@ fn main() -> ! {
|
||||||
}
|
}
|
||||||
Ok(Command::SetRpm(x)) => {
|
Ok(Command::SetRpm(x)) => {
|
||||||
rprintln!("SET_RPM with {}", x);
|
rprintln!("SET_RPM with {}", x);
|
||||||
_rpm = x;
|
target_rpm = x;
|
||||||
}
|
}
|
||||||
Ok(Command::SetTimer(x)) => {
|
Ok(Command::SetTimer(x)) => {
|
||||||
rprintln!("SETTING TIMER {}", x);
|
rprintln!("SETTING TIMER {}", x);
|
||||||
_timer = x;
|
timer = x as _;
|
||||||
}
|
}
|
||||||
Ok(Command::SendConfig) => {
|
Ok(Command::SendConfig) => {
|
||||||
rprintln!("SEND CONFIG");
|
rprintln!("SEND CONFIG");
|
||||||
|
|
@ -224,18 +222,20 @@ fn main() -> ! {
|
||||||
if started {
|
if started {
|
||||||
rprintln!("STARTING!");
|
rprintln!("STARTING!");
|
||||||
let _ = coat_timer
|
let _ = coat_timer
|
||||||
.load_value(esp_hal::time::Duration::from_secs(10))
|
.load_value(esp_hal::time::Duration::from_secs(timer))
|
||||||
.expect("TODO: Could not set timer for coating! ");
|
.expect("TODO: Could not set timer for coating! ");
|
||||||
dshot_esc.arm();
|
dshot_esc.arm();
|
||||||
let mut rpm_fail_ctr = 0;
|
let mut rpm_fail_ctr = 0;
|
||||||
|
let set_point = target_rpm;
|
||||||
coat_timer.start();
|
coat_timer.start();
|
||||||
|
let mut current_rpm = 0;
|
||||||
while !coat_timer.is_interrupt_set() {
|
while !coat_timer.is_interrupt_set() {
|
||||||
dshot_esc.process();
|
dshot_esc.process();
|
||||||
//let control_val = dc_driver::
|
//let control_val = dc_driver::
|
||||||
//this bad boy needs floats, this will be fun :)
|
//this bad boy needs floats, this will be fun :)
|
||||||
control = 200.00;
|
control = 200.00;
|
||||||
dshot_esc.set_throttle(control as _);
|
dshot_esc.set_throttle(control as _);
|
||||||
rpm = match dshot_esc.get_rpm() {
|
current_rpm = match dshot_esc.get_rpm() {
|
||||||
Some(x) => {
|
Some(x) => {
|
||||||
// rprintln!("GOT RPM {}", x);
|
// rprintln!("GOT RPM {}", x);
|
||||||
x
|
x
|
||||||
|
|
@ -243,7 +243,7 @@ fn main() -> ! {
|
||||||
None => {
|
None => {
|
||||||
rpm_fail_ctr+=1;
|
rpm_fail_ctr+=1;
|
||||||
// rprintln!("NO RPM!");
|
// rprintln!("NO RPM!");
|
||||||
rpm
|
current_rpm
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
// rprintln!("RPM:{}",rpm);
|
// rprintln!("RPM:{}",rpm);
|
||||||
|
|
@ -253,12 +253,12 @@ fn main() -> ! {
|
||||||
.duration_since_epoch()
|
.duration_since_epoch()
|
||||||
.as_millis();
|
.as_millis();
|
||||||
(control, ctx) =
|
(control, ctx) =
|
||||||
controller.compute(ctx, rpm as _, set_point as _, Millis(timestamp), None);
|
controller.compute(ctx, current_rpm as _, set_point as _, Millis(timestamp), None);
|
||||||
let dumped_context = ctx.last_time().expect("LAST TIME!");
|
let dumped_context = ctx.last_time().expect("LAST TIME!");
|
||||||
rprintln!("control:{},rpm:{}", control,rpm);
|
rprintln!("control:{},rpm:{}", control,current_rpm);
|
||||||
//first we send the RPM!
|
//first we send the RPM!
|
||||||
if display.write_ready(){
|
if display.write_ready(){
|
||||||
let running_rpm = format!("rpm.val={}", rpm);
|
let running_rpm = format!("rpm.val={}", current_rpm);
|
||||||
display.send_command(running_rpm.to_string().as_bytes());
|
display.send_command(running_rpm.to_string().as_bytes());
|
||||||
}
|
}
|
||||||
if display.write_ready(){
|
if display.write_ready(){
|
||||||
|
|
|
||||||
Loading…
Add table
Add a link
Reference in a new issue