mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Motors: add get_roll_thrust which returns roll input in range 0 to 1
Also added get_pitch_thrust, get_yaw_thrust
This commit is contained in:
parent
f73c8ab8ed
commit
3c74b4cc69
@ -71,6 +71,11 @@ public:
|
|||||||
float get_yaw() const { return _yaw_control_input; }
|
float get_yaw() const { return _yaw_control_input; }
|
||||||
float get_throttle() const { return _throttle_control_input; }
|
float get_throttle() const { return _throttle_control_input; }
|
||||||
|
|
||||||
|
// accessors for roll, pitch, yaw to motors within the range -1 ~ +1
|
||||||
|
float get_roll_thrust() const { return _roll_control_input / 4500.0f; }
|
||||||
|
float get_pitch_thrust() const { return _pitch_control_input / 4500.0f; }
|
||||||
|
float get_yaw_thrust() const { return _yaw_control_input / 4500.0f; }
|
||||||
|
|
||||||
void set_throttle_filter_cutoff(float filt_hz) { _throttle_filter.set_cutoff_frequency(filt_hz); }
|
void set_throttle_filter_cutoff(float filt_hz) { _throttle_filter.set_cutoff_frequency(filt_hz); }
|
||||||
|
|
||||||
//
|
//
|
||||||
|
Loading…
Reference in New Issue
Block a user