191 void AP_Motors6DOF::add_motor_raw_6dof(int8_t motor_num,
float roll_fac,
float pitch_fac,
float yaw_fac,
float throttle_fac,
float forward_fac,
float lat_fac, uint8_t testing_order)
194 add_motor_raw(motor_num, roll_fac, pitch_fac, yaw_fac, testing_order);
290 float throttle_thrust;
291 float forward_thrust;
292 float lateral_thrust;
361 float _current_change_rate = _batt_current_delta / loop_interval;
363 float predicted_current = _batt_current + (_current_change_rate * loop_interval * 5);
368 _batt_current_last = _batt_current;
371 batt_current_ratio = 2.5f;
372 }
else if (_batt_current < _batt_current_max && predicted_current >
_batt_current_max) {
373 batt_current_ratio = predicted_current_ratio;
396 float throttle_thrust;
397 float forward_thrust;
398 float lateral_thrust;
437 if (forward_coupling_limit < 0) {
438 forward_coupling_limit = 0;
440 int8_t forward_coupling_direction[] = {-1,-1,1,1,0,0,0,0,0,0,0,0};
447 float forward_thrust_limited = forward_thrust;
452 if (!
is_zero(forward_thrust_limited)) {
453 if ((forward_thrust < 0) == (forward_coupling_direction[i] < 0) && forward_coupling_direction[i] != 0) {
454 forward_thrust_limited =
constrain_float(forward_thrust, -forward_coupling_limit, forward_coupling_limit);
480 float throttle_thrust;
481 float forward_thrust;
482 float lateral_thrust;
520 if (fabsf(rpt_out[i]) > rpt_max) {
521 rpt_max = fabsf(rpt_out[i]);
534 if (fabsf(yfl_out[i]) > yfl_max) {
535 yfl_max = fabsf(yfl_out[i]);
Motor control class for ROVs with direct control over 6DOF (or fewer) in movement.
float _pitch_factor[AP_MOTORS_MAX_NUM_MOTORS]
void remove_motor(int8_t motor_num)
motor_frame_class _last_frame_class
float _yaw_factor[AP_MOTORS_MAX_NUM_MOTORS]
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
void add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, uint8_t testing_order)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
float _forward_factor[AP_MOTORS_MAX_NUM_MOTORS]
#define AP_GROUPINFO(name, idx, clazz, element, def)
int16_t _throttle_radio_max
AP_Float _forwardVerticalCouplingFactor
struct AP_Motors::AP_Motors_limit limit
void add_motor_raw_6dof(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, float climb_fac, float forward_fac, float lat_fac, uint8_t testing_order)
float get_current_limit_max_throttle() override
static const struct AP_Param::GroupInfo var_info[]
float get_throttle_bidirectional() const
void output_armed_stabilizing() override
int16_t calc_thrust_to_pwm(float thrust_in) const
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS]
bool is_zero(const T fVal1)
void setup_motors(motor_frame_class frame_class, motor_frame_type frame_type) override
bool has_current(uint8_t instance) const
has_current - returns true if battery monitor instance provides current info
void output_to_motors() override
float _lateral_factor[AP_MOTORS_MAX_NUM_MOTORS]
int16_t _throttle_radio_min
float current_amps(uint8_t instance) const
current_amps - returns the instantaneous current draw in amperes
AP_Float _batt_current_max
float _throttle_thrust_max
virtual void rc_write(uint8_t chan, uint16_t pwm)
AP_BattMonitor & battery()
float _roll_factor[AP_MOTORS_MAX_NUM_MOTORS]
float _thrust_rpyt_out[AP_MOTORS_MAX_NUM_MOTORS]
float constrain_float(const float amt, const float low, const float high)
#define AP_NESTEDGROUPINFO(clazz, idx)
AP_Int8 _motor_reverse[AP_MOTORS_MAX_NUM_MOTORS]
void output_min() override
spool_up_down_mode _spool_mode
void output_armed_stabilizing_vectored()
#define AP_MOTORS_MAX_NUM_MOTORS
void output_armed_stabilizing_vectored_6dof()
float _throttle_factor[AP_MOTORS_MAX_NUM_MOTORS]
AP_Float _batt_current_time_constant