RIT VEXU Core API
Loading...
Searching...
No Matches
feedforward.h
1#pragma once
2
3#include "../core/include/utils/math_util.h"
4#include "../core/include/utils/moving_average.h"
5#include "vex.h"
6#include <math.h>
7#include <vector>
8
30public:
39 typedef struct {
40 double kS;
41 double kV;
43 double kA;
45 double kG;
48
53 FeedForward(ff_config_t &cfg) : cfg(cfg) {}
54
65 double calculate(double v, double a, double pid_ref = 0.0) {
66 double ks_sign = 0;
67 if (v != 0)
68 ks_sign = sign(v);
69 else if (pid_ref != 0)
70 ks_sign = sign(pid_ref);
71
72 return (cfg.kS * ks_sign) + (cfg.kV * v) + (cfg.kA * a) + cfg.kG;
73 }
74
75private:
76 ff_config_t &cfg;
77};
78
86FeedForward::ff_config_t tune_feedforward(vex::motor_group &motor, double pct, double duration);
Definition feedforward.h:29
double calculate(double v, double a, double pid_ref=0.0)
Perform the feedforward calculation.
Definition feedforward.h:65
FeedForward(ff_config_t &cfg)
Definition feedforward.h:53
Definition feedforward.h:39
double kG
Definition feedforward.h:45
double kA
Definition feedforward.h:43
double kS
Definition feedforward.h:40
double kV
Definition feedforward.h:41