mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
Motors: add loop_rate to constructor
This commit is contained in:
parent
ec9d7dd99e
commit
77d4b3a2ae
@ -126,11 +126,12 @@ const AP_Param::GroupInfo AP_Motors::var_info[] PROGMEM = {
|
||||
};
|
||||
|
||||
// Constructor
|
||||
AP_Motors::AP_Motors( RC_Channel& rc_roll, RC_Channel& rc_pitch, RC_Channel& rc_throttle, RC_Channel& rc_yaw, uint16_t speed_hz ) :
|
||||
AP_Motors::AP_Motors(RC_Channel& rc_roll, RC_Channel& rc_pitch, RC_Channel& rc_throttle, RC_Channel& rc_yaw, uint16_t loop_rate, uint16_t speed_hz) :
|
||||
_rc_roll(rc_roll),
|
||||
_rc_pitch(rc_pitch),
|
||||
_rc_throttle(rc_throttle),
|
||||
_rc_yaw(rc_yaw),
|
||||
_loop_rate(loop_rate),
|
||||
_speed_hz(speed_hz),
|
||||
_min_throttle(AP_MOTORS_DEFAULT_MIN_THROTTLE),
|
||||
_max_throttle(AP_MOTORS_DEFAULT_MAX_THROTTLE),
|
||||
|
@ -85,7 +85,7 @@ class AP_Motors {
|
||||
public:
|
||||
|
||||
// Constructor
|
||||
AP_Motors( RC_Channel& rc_roll, RC_Channel& rc_pitch, RC_Channel& rc_throttle, RC_Channel& rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT);
|
||||
AP_Motors(RC_Channel& rc_roll, RC_Channel& rc_pitch, RC_Channel& rc_throttle, RC_Channel& rc_yaw, uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT);
|
||||
|
||||
// init
|
||||
virtual void Init();
|
||||
@ -211,6 +211,7 @@ protected:
|
||||
RC_Channel& _rc_pitch; // pitch input in from users is held in servo_out
|
||||
RC_Channel& _rc_throttle; // throttle input in from users is held in servo_out
|
||||
RC_Channel& _rc_yaw; // yaw input in from users is held in servo_out
|
||||
uint16_t _loop_rate; // rate at which output() function is called (normally 400hz)
|
||||
uint16_t _speed_hz; // speed in hz to send updates to motors
|
||||
int16_t _min_throttle; // the minimum throttle to be sent to the motors when they're on (prevents motors stalling while flying)
|
||||
int16_t _max_throttle; // the maximum throttle to be sent to the motors (sometimes limited by slow start)
|
||||
|
Loading…
Reference in New Issue
Block a user