AR_Motors: remove AP_ServoRelayEvents from AP_MotorsUGV interface

instead, take it from the singleton
This commit is contained in:
Peter Barker 2023-06-06 17:08:29 +10:00 committed by Peter Barker
parent 320bd43334
commit 8532444bb5
2 changed files with 6 additions and 6 deletions

View File

@ -16,6 +16,7 @@
#include <SRV_Channel/SRV_Channel.h>
#include <GCS_MAVLink/GCS.h>
#include "AP_MotorsUGV.h"
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
#define SERVO_MAX 4500 // This value represents 45 degrees and is just an arbitrary representation of servo max travel.
@ -113,8 +114,7 @@ const AP_Param::GroupInfo AP_MotorsUGV::var_info[] = {
AP_GROUPEND
};
AP_MotorsUGV::AP_MotorsUGV(AP_ServoRelayEvents &relayEvents, AP_WheelRateControl& rate_controller) :
_relayEvents(relayEvents),
AP_MotorsUGV::AP_MotorsUGV(AP_WheelRateControl& rate_controller) :
_rate_controller(rate_controller)
{
AP_Param::setup_object_defaults(this, var_info);
@ -847,6 +847,8 @@ void AP_MotorsUGV::output_throttle(SRV_Channel::Aux_servo_function_t function, f
// set relay if necessary
if (_pwm_type == PWM_TYPE_BRUSHED_WITH_RELAY) {
auto &_relayEvents { *AP::servorelayevents() };
// find the output channel, if not found return
const SRV_Channel *out_chan = SRV_Channels::get_channel_for(function);
if (out_chan == nullptr) {

View File

@ -1,14 +1,13 @@
#pragma once
#include <AP_Arming/AP_Arming.h>
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
#include <AP_WheelEncoder/AP_WheelRateControl.h>
#include <SRV_Channel/SRV_Channel.h>
class AP_MotorsUGV {
public:
// Constructor
AP_MotorsUGV(AP_ServoRelayEvents &relayEvents, AP_WheelRateControl& rate_controller);
AP_MotorsUGV(AP_WheelRateControl& rate_controller);
// singleton support
static AP_MotorsUGV *get_singleton(void) { return _singleton; }
@ -190,7 +189,6 @@ private:
float get_rate_controlled_throttle(SRV_Channel::Aux_servo_function_t function, float throttle, float dt);
// external references
AP_ServoRelayEvents &_relayEvents;
AP_WheelRateControl &_rate_controller;
static const int8_t AP_MOTORS_NUM_MOTORS_MAX = 4;