APM:Libraries
AP_SteerController.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_AHRS/AP_AHRS.h>
4 #include <AP_Common/AP_Common.h>
6 #include <DataFlash/DataFlash.h>
7 
9 public:
11  : _ahrs(ahrs)
12  {
14  }
15 
16  /* Do not allow copies */
17  AP_SteerController(const AP_SteerController &other) = delete;
19 
20  /*
21  return a steering servo output from -4500 to 4500 given a
22  desired lateral acceleration rate in m/s/s. Positive lateral
23  acceleration is to the right.
24  */
25  int32_t get_steering_out_lat_accel(float desired_accel);
26 
27  /*
28  return a steering servo output from -4500 to 4500 given a
29  desired yaw rate in degrees/sec. Positive yaw is to the right.
30  */
31  int32_t get_steering_out_rate(float desired_rate);
32 
33  /*
34  return a steering servo output from -4500 to 4500 given a
35  yaw error in centi-degrees
36  */
37  int32_t get_steering_out_angle_error(int32_t angle_err);
38 
39  /*
40  return the steering radius (half diameter). Assumed to be half
41  the P value.
42  */
43  float get_turn_radius(void) const { return _K_P * 0.5f; }
44 
45  void reset_I();
46 
47  static const struct AP_Param::GroupInfo var_info[];
48 
49  const DataFlash_Class::PID_Info& get_pid_info(void) const { return _pid_info; }
50 
51  void set_reverse(bool reverse) {
52  _reverse = reverse;
53  }
54 
55 private:
56  AP_Float _tau;
57  AP_Float _K_FF;
58  AP_Float _K_P;
59  AP_Float _K_I;
60  AP_Float _K_D;
61  AP_Float _minspeed;
62  AP_Int16 _imax;
63  uint32_t _last_t;
64  float _last_out;
65 
66  AP_Float _deratespeed;
67  AP_Float _deratefactor;
68  AP_Float _mindegree;
69 
71 
73 
74  bool _reverse;
75 };
AP_SteerController(AP_AHRS &ahrs)
void set_reverse(bool reverse)
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
AP_SteerController & operator=(const AP_SteerController &)=delete
float get_turn_radius(void) const
int32_t get_steering_out_lat_accel(float desired_accel)
Common definitions and utility routines for the ArduPilot libraries.
DataFlash_Class::PID_Info _pid_info
const DataFlash_Class::PID_Info & get_pid_info(void) const
int32_t get_steering_out_rate(float desired_rate)
static const struct AP_Param::GroupInfo var_info[]
int32_t get_steering_out_angle_error(int32_t angle_err)
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214