mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AC_AttControl_Multi: new multirotor specific attitude control class
This commit is contained in:
parent
93dd7dd970
commit
bf2bf2e3fa
22
libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp
Normal file
22
libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp
Normal file
@ -0,0 +1,22 @@
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
#include "AC_AttitudeControl_Multi.h"
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_Math.h>
|
||||
|
||||
// returns a throttle including compensation for roll/pitch angle
|
||||
// throttle value should be 0 ~ 1000
|
||||
float AC_AttitudeControl_Multi::get_boosted_throttle(float throttle_in)
|
||||
{
|
||||
// inverted_factor is 1 for tilt angles below 60 degrees
|
||||
// reduces as a function of angle beyond 60 degrees
|
||||
// becomes zero at 90 degrees
|
||||
float min_throttle = _motors_multi.throttle_min();
|
||||
float cos_tilt = _ahrs.cos_pitch() * _ahrs.cos_roll();
|
||||
float inverted_factor = constrain_float(2.0f*cos_tilt, 0.0f, 1.0f);
|
||||
float boost_factor = 1.0f/constrain_float(cos_tilt, 0.5f, 1.0f);
|
||||
|
||||
float throttle_out = (throttle_in-min_throttle)*inverted_factor*boost_factor + min_throttle;
|
||||
_angle_boost = constrain_float(throttle_out - throttle_in,-32000,32000);
|
||||
return throttle_out;
|
||||
}
|
35
libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h
Normal file
35
libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h
Normal file
@ -0,0 +1,35 @@
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
/// @file AC_AttitudeControl_Multi.h
|
||||
/// @brief ArduCopter attitude control library
|
||||
|
||||
#ifndef AC_AttitudeControl_Multi_H
|
||||
#define AC_AttitudeControl_Multi_H
|
||||
|
||||
#include <AC_AttitudeControl.h>
|
||||
#include <AP_MotorsMulticopter.h>
|
||||
|
||||
class AC_AttitudeControl_Multi : public AC_AttitudeControl {
|
||||
public:
|
||||
AC_AttitudeControl_Multi(AP_AHRS &ahrs,
|
||||
const AP_Vehicle::MultiCopter &aparm,
|
||||
AP_MotorsMulticopter& motors,
|
||||
AC_P& pi_angle_roll, AC_P& pi_angle_pitch, AC_P& pi_angle_yaw,
|
||||
AC_PID& pid_rate_roll, AC_PID& pid_rate_pitch, AC_PID& pid_rate_yaw
|
||||
) :
|
||||
AC_AttitudeControl(ahrs, aparm, motors, pi_angle_roll, pi_angle_pitch, pi_angle_yaw, pid_rate_roll, pid_rate_pitch, pid_rate_yaw),
|
||||
_motors_multi(motors)
|
||||
{}
|
||||
|
||||
// empty destructor to suppress compiler warning
|
||||
virtual ~AC_AttitudeControl_Multi() {}
|
||||
|
||||
// calculate total body frame throttle required to produce the given earth frame throttle
|
||||
float get_boosted_throttle(float throttle_in);
|
||||
|
||||
protected:
|
||||
|
||||
AP_MotorsMulticopter& _motors_multi;
|
||||
};
|
||||
|
||||
#endif // AC_AttitudeControl_Multi_H
|
Loading…
Reference in New Issue
Block a user