SRV_Channel: adding Volz Support

This commit is contained in:
Guy Tzoler 2017-11-03 13:27:29 +11:00 committed by Andrew Tridgell
parent 2442f3fb06
commit 7f68be9bdf
2 changed files with 38 additions and 0 deletions

View File

@ -17,6 +17,7 @@
#include <AP_Param/AP_Param.h>
#include <AP_RCMapper/AP_RCMapper.h>
#include <AP_Common/Bitmask.h>
#include <AP_Volz_Protocol/AP_Volz_Protocol.h>
#define NUM_SERVO_CHANNELS 16
@ -30,6 +31,7 @@ class SRV_Channels;
class SRV_Channel {
public:
friend class SRV_Channels;
// constructor
SRV_Channel(void);
@ -414,6 +416,10 @@ public:
return SRV_Channel::Aux_servo_function_t((SRV_Channel::k_motor9+(channel-8)));
}
static void cork();
static void push();
private:
struct {
bool k_throttle_reversible:1;
@ -429,6 +435,11 @@ private:
// this static arrangement is to avoid having static objects in AP_Param tables
static SRV_Channel *channels;
static SRV_Channels *instance;
// support for Volz protocol
AP_Volz_Protocol volz = AP_Volz_Protocol::create();
static AP_Volz_Protocol *volz_ptr;
SRV_Channel obj_channels[NUM_SERVO_CHANNELS];
static struct srv_function {

View File

@ -26,6 +26,8 @@ extern const AP_HAL::HAL& hal;
SRV_Channel *SRV_Channels::channels;
SRV_Channels *SRV_Channels::instance;
AP_Volz_Protocol *SRV_Channels::volz_ptr;
bool SRV_Channels::disabled_passthrough;
bool SRV_Channels::initialised;
Bitmask SRV_Channels::function_mask{SRV_Channel::k_nr_aux_servo_functions};
@ -111,6 +113,10 @@ const AP_Param::GroupInfo SRV_Channels::var_info[] = {
// @Units: Hz
AP_GROUPINFO("_RATE", 18, SRV_Channels, default_rate, 50),
// @Group: VOLZ_
// @Path: ../AP_Volz_Protocol/AP_Volz_Protocol.cpp
AP_SUBGROUPINFO(volz, "_VOLZ_", 19, SRV_Channels, AP_Volz_Protocol),
AP_GROUPEND
};
@ -129,6 +135,8 @@ SRV_Channels::SRV_Channels(void)
for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
channels[i].ch_num = i;
}
volz_ptr = &volz;
}
/*
@ -175,3 +183,22 @@ void SRV_Channels::set_output_pwm_chan(uint8_t chan, uint16_t value)
channels[chan].set_output_pwm(value);
}
}
/*
wrapper around hal.rcout->cork()
*/
void SRV_Channels::cork()
{
hal.rcout->cork();
}
/*
wrapper around hal.rcout->push()
*/
void SRV_Channels::push()
{
hal.rcout->push();
// give volz library a chance to update
volz_ptr->update();
}