2017-07-06 00:07:12 -03:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include "defines.h"
|
|
|
|
#include "AP_Arming.h"
|
2017-07-06 00:23:42 -03:00
|
|
|
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
|
2017-07-06 00:07:12 -03:00
|
|
|
|
|
|
|
class AP_MotorsUGV {
|
|
|
|
public:
|
|
|
|
// Constructor
|
2017-07-06 00:23:42 -03:00
|
|
|
AP_MotorsUGV(AP_ServoRelayEvents &relayEvents);
|
2017-07-06 00:07:12 -03:00
|
|
|
|
|
|
|
enum pwm_type {
|
|
|
|
PWM_TYPE_NORMAL = 0,
|
|
|
|
PWM_TYPE_ONESHOT = 1,
|
|
|
|
PWM_TYPE_ONESHOT125 = 2,
|
2017-08-21 21:24:34 -03:00
|
|
|
PWM_TYPE_BRUSHED_WITH_RELAY = 3,
|
|
|
|
PWM_TYPE_BRUSHED_BIPOLAR = 4,
|
2018-12-17 06:47:43 -04:00
|
|
|
PWM_TYPE_DSHOT150 = 5,
|
|
|
|
PWM_TYPE_DSHOT300 = 6,
|
|
|
|
PWM_TYPE_DSHOT600 = 7,
|
|
|
|
PWM_TYPE_DSHOT1200 = 8
|
2020-05-23 17:51:49 -03:00
|
|
|
};
|
2017-07-06 00:07:12 -03:00
|
|
|
|
2017-07-14 23:57:38 -03:00
|
|
|
enum motor_test_order {
|
2017-07-17 04:41:10 -03:00
|
|
|
MOTOR_TEST_THROTTLE = 1,
|
|
|
|
MOTOR_TEST_STEERING = 2,
|
|
|
|
MOTOR_TEST_THROTTLE_LEFT = 3,
|
|
|
|
MOTOR_TEST_THROTTLE_RIGHT = 4,
|
2018-11-05 18:00:33 -04:00
|
|
|
MOTOR_TEST_MAINSAIL = 5,
|
|
|
|
MOTOR_TEST_LAST
|
2017-07-14 23:57:38 -03:00
|
|
|
};
|
|
|
|
|
2019-01-23 22:51:10 -04:00
|
|
|
// supported omni motor configurations
|
2018-05-31 06:26:07 -03:00
|
|
|
enum frame_type {
|
|
|
|
FRAME_TYPE_UNDEFINED = 0,
|
|
|
|
FRAME_TYPE_OMNI3 = 1,
|
|
|
|
FRAME_TYPE_OMNIX = 2,
|
|
|
|
FRAME_TYPE_OMNIPLUS = 3,
|
|
|
|
};
|
|
|
|
|
2017-07-06 00:07:12 -03:00
|
|
|
// initialise motors
|
|
|
|
void init();
|
|
|
|
|
2018-06-06 03:18:24 -03:00
|
|
|
// return true if motors are active
|
|
|
|
bool active() const;
|
|
|
|
|
2017-07-06 00:07:12 -03:00
|
|
|
// setup output in case of main CPU failure
|
|
|
|
void setup_safety_output();
|
|
|
|
|
2017-08-15 22:00:40 -03:00
|
|
|
// setup servo output ranges
|
2017-07-06 07:01:53 -03:00
|
|
|
void setup_servo_output();
|
|
|
|
|
2017-08-15 22:31:49 -03:00
|
|
|
// get or set steering as a value from -4500 to +4500
|
2018-05-03 05:54:13 -03:00
|
|
|
// apply_scaling should be set to false for manual modes where
|
|
|
|
// no scaling by speed or angle should e performed
|
2017-07-06 00:07:12 -03:00
|
|
|
float get_steering() const { return _steering; }
|
2018-05-03 05:54:13 -03:00
|
|
|
void set_steering(float steering, bool apply_scaling = true);
|
2017-07-06 00:07:12 -03:00
|
|
|
|
2017-08-15 22:31:49 -03:00
|
|
|
// get or set throttle as a value from -100 to 100
|
2017-07-06 00:07:12 -03:00
|
|
|
float get_throttle() const { return _throttle; }
|
2017-08-15 22:31:49 -03:00
|
|
|
void set_throttle(float throttle);
|
2017-07-06 00:07:12 -03:00
|
|
|
|
2020-07-22 10:42:56 -03:00
|
|
|
// get or set roll as a value from -1 to 1
|
|
|
|
float get_roll() const { return _roll; }
|
|
|
|
void set_roll(float roll);
|
|
|
|
|
|
|
|
// get or set pitch as a value from -1 to 1
|
|
|
|
float get_pitch() const { return _pitch; }
|
|
|
|
void set_pitch(float pitch);
|
|
|
|
|
2020-08-28 15:51:26 -03:00
|
|
|
// get or set walking_height as a value from -1 to 1
|
|
|
|
float get_walking_height() const { return _walking_height; }
|
|
|
|
void set_walking_height(float walking_height);
|
|
|
|
|
2020-08-07 20:02:27 -03:00
|
|
|
// get or set lateral input as a value from -100 to +100
|
|
|
|
float get_lateral() const { return _lateral; }
|
2018-05-10 04:10:34 -03:00
|
|
|
void set_lateral(float lateral);
|
|
|
|
|
2019-09-27 16:01:39 -03:00
|
|
|
// set or get mainsail input as a value from 0 to 100
|
2018-09-14 03:46:25 -03:00
|
|
|
void set_mainsail(float mainsail);
|
|
|
|
float get_mainsail() const { return _mainsail; }
|
|
|
|
|
2019-09-27 16:01:39 -03:00
|
|
|
// set or get wingsail input as a value from -100 to 100
|
|
|
|
void set_wingsail(float wingsail);
|
|
|
|
float get_wingsail() const { return _wingsail; }
|
|
|
|
|
2021-04-27 16:50:36 -03:00
|
|
|
// set or get mast rotation input as a value from -100 to 100
|
|
|
|
void set_mast_rotation(float mast_rotation);
|
|
|
|
float get_mast_rotation() const { return _mast_rotation; }
|
|
|
|
|
2018-05-06 05:08:51 -03:00
|
|
|
// get slew limited throttle
|
|
|
|
// used by manual mode to avoid bad steering behaviour during transitions from forward to reverse
|
|
|
|
// same as private slew_limit_throttle method (see below) but does not update throttle state
|
|
|
|
float get_slew_limited_throttle(float throttle, float dt) const;
|
|
|
|
|
2017-07-06 00:07:12 -03:00
|
|
|
// true if vehicle is capable of skid steering
|
|
|
|
bool have_skid_steering() const;
|
|
|
|
|
2018-04-09 09:09:49 -03:00
|
|
|
// true if vehicle has vectored thrust (i.e. boat with motor on steering servo)
|
2021-03-31 04:09:15 -03:00
|
|
|
bool have_vectored_thrust() const { return is_positive(_vector_angle_max); }
|
2018-04-09 09:09:49 -03:00
|
|
|
|
2017-07-06 00:07:12 -03:00
|
|
|
// output to motors and steering servos
|
2018-05-03 05:54:13 -03:00
|
|
|
// ground_speed should be the vehicle's speed over the surface in m/s
|
|
|
|
// dt should be expected time between calls to this function
|
|
|
|
void output(bool armed, float ground_speed, float dt);
|
2017-07-06 00:07:12 -03:00
|
|
|
|
2017-07-15 04:21:13 -03:00
|
|
|
// test steering or throttle output as a percentage of the total (range -100 to +100)
|
|
|
|
// used in response to DO_MOTOR_TEST mavlink command
|
|
|
|
bool output_test_pct(motor_test_order motor_seq, float pct);
|
|
|
|
|
|
|
|
// test steering or throttle output using a pwm value
|
|
|
|
bool output_test_pwm(motor_test_order motor_seq, float pwm);
|
2017-07-14 23:57:38 -03:00
|
|
|
|
2017-12-09 02:54:22 -04:00
|
|
|
// returns true if checks pass, false if they fail. display_failure argument should be true to send text messages to GCS
|
|
|
|
bool pre_arm_check(bool report) const;
|
|
|
|
|
2017-08-09 04:20:44 -03:00
|
|
|
// structure for holding motor limit flags
|
|
|
|
struct AP_MotorsUGV_limit {
|
|
|
|
uint8_t steer_left : 1; // we have reached the steering controller's left most limit
|
|
|
|
uint8_t steer_right : 1; // we have reached the steering controller's right most limit
|
|
|
|
uint8_t throttle_lower : 1; // we have reached throttle's lower limit
|
|
|
|
uint8_t throttle_upper : 1; // we have reached throttle's upper limit
|
|
|
|
} limit;
|
|
|
|
|
2017-07-06 00:07:12 -03:00
|
|
|
// var_info for holding Parameter information
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
|
|
|
protected:
|
2018-05-02 05:19:12 -03:00
|
|
|
// sanity check parameters
|
|
|
|
void sanity_check_parameters();
|
|
|
|
|
2017-07-06 00:07:12 -03:00
|
|
|
// setup pwm output type
|
|
|
|
void setup_pwm_type();
|
|
|
|
|
2019-01-23 22:55:47 -04:00
|
|
|
// setup for frames with omni motors
|
|
|
|
void setup_omni();
|
|
|
|
|
|
|
|
// add omni motor using separate throttle, steering and lateral factors
|
|
|
|
void add_omni_motor(int8_t motor_num, float throttle_factor, float steering_factor, float lateral_factor);
|
|
|
|
|
|
|
|
// add a motor and set up output function
|
|
|
|
void add_omni_motor_num(int8_t motor_num);
|
|
|
|
|
|
|
|
// disable omni motor and remove all throttle, steering and lateral factor for this motor
|
|
|
|
void clear_omni_motors(int8_t motor_num);
|
|
|
|
|
2017-07-06 00:07:12 -03:00
|
|
|
// output to regular steering and throttle channels
|
2018-05-03 05:54:13 -03:00
|
|
|
void output_regular(bool armed, float ground_speed, float steering, float throttle);
|
2017-07-06 00:07:12 -03:00
|
|
|
|
|
|
|
// output to skid steering channels
|
2018-08-07 04:15:05 -03:00
|
|
|
void output_skid_steering(bool armed, float steering, float throttle, float dt);
|
2017-07-06 00:07:12 -03:00
|
|
|
|
2019-01-23 22:51:10 -04:00
|
|
|
// output for omni motors
|
|
|
|
void output_omni(bool armed, float steering, float throttle, float lateral);
|
2018-05-31 06:26:07 -03:00
|
|
|
|
2017-07-12 05:31:56 -03:00
|
|
|
// output throttle (-100 ~ +100) to a throttle channel. Sets relays if required
|
2018-08-07 04:15:05 -03:00
|
|
|
// dt is the main loop time interval and is required when rate control is required
|
|
|
|
void output_throttle(SRV_Channel::Aux_servo_function_t function, float throttle, float dt = 0.0f);
|
2017-07-12 05:31:56 -03:00
|
|
|
|
2019-09-27 16:01:39 -03:00
|
|
|
// output for sailboat's mainsail in the range of 0 to 100 and wing sail in the range +- 100
|
|
|
|
void output_sail();
|
2018-09-14 03:46:25 -03:00
|
|
|
|
2019-09-27 16:01:39 -03:00
|
|
|
// true if the vehicle has a mainsail or wing sail
|
2019-05-14 13:36:10 -03:00
|
|
|
bool has_sail() const;
|
|
|
|
|
2017-07-06 00:07:12 -03:00
|
|
|
// slew limit throttle for one iteration
|
|
|
|
void slew_limit_throttle(float dt);
|
|
|
|
|
2017-08-09 04:20:44 -03:00
|
|
|
// set limits based on steering and throttle input
|
|
|
|
void set_limits_from_input(bool armed, float steering, float throttle);
|
|
|
|
|
2017-12-01 09:27:30 -04:00
|
|
|
// scale a throttle using the _thrust_curve_expo parameter. throttle should be in the range -100 to +100
|
|
|
|
float get_scaled_throttle(float throttle) const;
|
|
|
|
|
2018-08-07 04:15:05 -03:00
|
|
|
// use rate controller to achieve desired throttle
|
|
|
|
float get_rate_controlled_throttle(SRV_Channel::Aux_servo_function_t function, float throttle, float dt);
|
|
|
|
|
2017-07-06 00:23:42 -03:00
|
|
|
// external references
|
|
|
|
AP_ServoRelayEvents &_relayEvents;
|
|
|
|
|
2018-05-31 06:26:07 -03:00
|
|
|
static const int8_t AP_MOTORS_NUM_MOTORS_MAX = 4;
|
|
|
|
|
2017-07-06 00:07:12 -03:00
|
|
|
// parameters
|
|
|
|
AP_Int8 _pwm_type; // PWM output type
|
|
|
|
AP_Int8 _pwm_freq; // PWM output freq for brushed motors
|
|
|
|
AP_Int8 _disarm_disable_pwm; // disable PWM output while disarmed
|
2017-11-27 02:18:04 -04:00
|
|
|
AP_Int16 _slew_rate; // slew rate expressed as a percentage / second
|
2017-08-15 22:31:49 -03:00
|
|
|
AP_Int8 _throttle_min; // throttle minimum percentage
|
|
|
|
AP_Int8 _throttle_max; // throttle maximum percentage
|
2017-12-01 09:27:30 -04:00
|
|
|
AP_Float _thrust_curve_expo; // thrust curve exponent from -1 to +1 with 0 being linear
|
2021-03-31 04:09:15 -03:00
|
|
|
AP_Float _vector_angle_max; // angle between steering's middle position and maximum position when using vectored thrust. zero to disable vectored thrust
|
2018-06-07 23:03:44 -03:00
|
|
|
AP_Float _speed_scale_base; // speed above which steering is scaled down when using regular steering/throttle vehicles. zero to disable speed scaling
|
2020-07-30 22:01:13 -03:00
|
|
|
AP_Float _steering_throttle_mix; // Steering vs Throttle priorisation. Higher numbers prioritise steering, lower numbers prioritise throttle. Only valid for Skid Steering vehicles
|
2017-07-06 00:07:12 -03:00
|
|
|
|
|
|
|
// internal variables
|
|
|
|
float _steering; // requested steering as a value from -4500 to +4500
|
2017-08-15 23:42:28 -03:00
|
|
|
float _throttle; // requested throttle as a value from -100 to 100
|
2017-11-21 20:43:30 -04:00
|
|
|
float _throttle_prev; // throttle input from previous iteration
|
2018-05-03 05:54:13 -03:00
|
|
|
bool _scale_steering = true; // true if we should scale steering by speed or angle
|
2018-05-31 06:26:07 -03:00
|
|
|
float _lateral; // requested lateral input as a value from -100 to +100
|
2020-07-22 10:42:56 -03:00
|
|
|
float _roll; // requested roll as a value from -1 to +1
|
|
|
|
float _pitch; // requested pitch as a value from -1 to +1
|
2020-08-28 15:51:26 -03:00
|
|
|
float _walking_height; // requested height as a value from -1 to +1
|
2018-09-14 03:46:25 -03:00
|
|
|
float _mainsail; // requested mainsail input as a value from 0 to 100
|
2019-09-27 16:01:39 -03:00
|
|
|
float _wingsail; // requested wing sail input as a value in the range +- 100
|
2021-04-27 16:50:36 -03:00
|
|
|
float _mast_rotation; // requested mast rotation input as a value in the range +- 100
|
2018-05-31 06:26:07 -03:00
|
|
|
|
2019-01-23 22:51:10 -04:00
|
|
|
// omni variables
|
2018-05-31 06:26:07 -03:00
|
|
|
float _throttle_factor[AP_MOTORS_NUM_MOTORS_MAX];
|
|
|
|
float _steering_factor[AP_MOTORS_NUM_MOTORS_MAX];
|
|
|
|
float _lateral_factor[AP_MOTORS_NUM_MOTORS_MAX];
|
|
|
|
uint8_t _motors_num;
|
2017-07-06 00:07:12 -03:00
|
|
|
};
|