2013-09-08 21:17:02 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
#ifndef __AP_STEER_CONTROLLER_H__
|
|
|
|
#define __AP_STEER_CONTROLLER_H__
|
|
|
|
|
|
|
|
#include <AP_AHRS.h>
|
|
|
|
#include <AP_Common.h>
|
2013-09-12 22:46:22 -03:00
|
|
|
#include <AP_Vehicle.h>
|
2015-06-08 08:08:14 -03:00
|
|
|
#include <DataFlash.h>
|
2013-09-08 21:17:02 -03:00
|
|
|
|
|
|
|
class AP_SteerController {
|
|
|
|
public:
|
|
|
|
AP_SteerController(AP_AHRS &ahrs) :
|
|
|
|
_ahrs(ahrs)
|
|
|
|
{
|
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
return a steering servo output from -4500 to 4500 given a
|
2013-10-03 08:54:11 -03:00
|
|
|
desired lateral acceleration rate in m/s/s. Positive lateral
|
|
|
|
acceleration is to the right.
|
2013-09-08 21:17:02 -03:00
|
|
|
*/
|
2013-10-03 08:54:11 -03:00
|
|
|
int32_t get_steering_out_lat_accel(float desired_accel);
|
|
|
|
|
|
|
|
/*
|
|
|
|
return a steering servo output from -4500 to 4500 given a
|
|
|
|
desired yaw rate in degrees/sec. Positive yaw is to the right.
|
|
|
|
*/
|
|
|
|
int32_t get_steering_out_rate(float desired_rate);
|
|
|
|
|
|
|
|
/*
|
|
|
|
return a steering servo output from -4500 to 4500 given a
|
|
|
|
yaw error in centi-degrees
|
|
|
|
*/
|
|
|
|
int32_t get_steering_out_angle_error(int32_t angle_err);
|
2013-09-08 21:17:02 -03:00
|
|
|
|
2013-09-29 20:03:52 -03:00
|
|
|
/*
|
|
|
|
return the steering radius (half diameter). Assumed to be half
|
|
|
|
the P value.
|
|
|
|
*/
|
|
|
|
float get_turn_radius(void) const { return _K_P * 0.5f; }
|
|
|
|
|
2013-09-08 21:17:02 -03:00
|
|
|
void reset_I();
|
|
|
|
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
2015-06-08 08:08:14 -03:00
|
|
|
const DataFlash_Class::PID_Info& get_pid_info(void) const { return _pid_info; }
|
|
|
|
|
2013-09-08 21:17:02 -03:00
|
|
|
private:
|
|
|
|
AP_Float _tau;
|
2015-06-08 08:08:14 -03:00
|
|
|
AP_Float _K_FF;
|
2013-09-08 21:17:02 -03:00
|
|
|
AP_Float _K_P;
|
|
|
|
AP_Float _K_I;
|
|
|
|
AP_Float _K_D;
|
2013-09-29 20:03:52 -03:00
|
|
|
AP_Float _minspeed;
|
2013-09-08 21:17:02 -03:00
|
|
|
AP_Int16 _imax;
|
|
|
|
uint32_t _last_t;
|
|
|
|
float _last_out;
|
|
|
|
|
2015-06-08 08:08:14 -03:00
|
|
|
DataFlash_Class::PID_Info _pid_info {};
|
2013-09-08 21:17:02 -03:00
|
|
|
|
|
|
|
AP_AHRS &_ahrs;
|
|
|
|
};
|
|
|
|
|
|
|
|
#endif // __AP_STEER_CONTROLLER_H__
|