pub struct ArmFeedForward { /* private fields */ }Expand description
Feedforward controller for arm mechanisms with gravity compensation.
Extends FeedForward with a gravity compensation term that accounts for
the arm’s position. This is essential for arms that must hold position
against gravity.
§Formula
voltage = ks * sign(v) + kv * v + ka * a + kg * g(angle)Where g(angle) is a function that returns the gravity effect at the given
angle (typically cos(angle) for a simple arm).
§Example
use kernelvex::{ArmFeedForward, QAngle};
let ff = ArmFeedForward::new(0.1, 0.5, 0.01, 0.3);
// Calculate with gravity compensation using cosine
let voltage = ff.calculate(
QAngle::from_degrees(45.0),
target_velocity,
target_acceleration,
|angle| angle.cos(),
);Implementations§
Source§impl ArmFeedForward
impl ArmFeedForward
Sourcepub const fn new(ks: f64, kv: f64, ka: f64, kg: f64) -> Self
pub const fn new(ks: f64, kv: f64, ka: f64, kg: f64) -> Self
Creates a new arm feedforward controller with the given gains.
§Arguments
ks- Static friction compensationkv- Velocity feedforward gainka- Acceleration feedforward gainkg- Gravity compensation gain
Sourcepub const fn set_gains(self, ks: f64, kv: f64, ka: f64, kg: f64) -> Self
pub const fn set_gains(self, ks: f64, kv: f64, ka: f64, kg: f64) -> Self
Sets all gains at once, returning a new instance.
Sourcepub const fn set_ks(self, ks: f64) -> Self
pub const fn set_ks(self, ks: f64) -> Self
Sets the static friction gain, returning a new instance.
Sourcepub const fn set_ka(self, ka: f64) -> Self
pub const fn set_ka(self, ka: f64) -> Self
Sets the acceleration gain, returning a new instance.
Sourcepub fn calculate(
&self,
angle: QAngle,
velocity: f64,
acceleration: f64,
g: impl Fn(QAngle) -> f64,
) -> f64
pub fn calculate( &self, angle: QAngle, velocity: f64, acceleration: f64, g: impl Fn(QAngle) -> f64, ) -> f64
Calculates the feedforward voltage with gravity compensation.
§Arguments
angle- Current arm anglevelocity- Desired velocityacceleration- Desired accelerationg- Gravity function that takes angle and returns gravity effect
§Returns
The feedforward voltage output including gravity compensation.
§Example
// Using cosine for simple arm
let voltage = ff.calculate(angle, vel, acc, |a| a.cos());
// Using custom gravity function
let voltage = ff.calculate(angle, vel, acc, |a| {
// Custom gravity calculation for 4-bar linkage
(a + offset).cos() * linkage_factor
});Auto Trait Implementations§
impl Freeze for ArmFeedForward
impl RefUnwindSafe for ArmFeedForward
impl Send for ArmFeedForward
impl Sync for ArmFeedForward
impl Unpin for ArmFeedForward
impl UnsafeUnpin for ArmFeedForward
impl UnwindSafe for ArmFeedForward
Blanket Implementations§
Source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Mutably borrows from an owned value. Read more
Source§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
Source§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
The inverse inclusion map: attempts to construct
self from the equivalent element of its
superset. Read moreSource§fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
Checks if
self is actually part of its subset T (and can be converted to it).Source§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
Use with care! Same as
self.to_subset but without any property checks. Always succeeds.Source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
The inclusion map: converts
self to the equivalent element of its superset.