Plane: added servo remapping object
This commit is contained in:
parent
c7f8b255e7
commit
8170df7ba8
@ -1378,6 +1378,10 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
// @Group: ICE_
|
||||
// @Path: ../libraries/AP_ICEngine/AP_ICEngine.cpp
|
||||
AP_SUBGROUPINFO(ice_control, "ICE_", 2, ParametersG2, AP_ICEngine),
|
||||
|
||||
// @Group: SERVO_
|
||||
// @Path: ../libraries/RC_Channel/SRV_Channel.cpp
|
||||
AP_SUBGROUPINFO(servo_channels, "SERVO", 3, ParametersG2, SRV_Channels),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
@ -585,6 +585,9 @@ public:
|
||||
|
||||
// internal combustion engine control
|
||||
AP_ICEngine ice_control;
|
||||
|
||||
// control over servo output ranges
|
||||
SRV_Channels servo_channels;
|
||||
};
|
||||
|
||||
extern const AP_Param::Info var_info[];
|
||||
|
@ -44,6 +44,7 @@
|
||||
#include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
|
||||
#include <AP_AHRS/AP_AHRS.h> // ArduPilot Mega DCM Library
|
||||
#include <RC_Channel/RC_Channel.h> // RC Channel Library
|
||||
#include <RC_Channel/SRV_Channel.h>
|
||||
#include <AP_RangeFinder/AP_RangeFinder.h> // Range finder library
|
||||
#include <Filter/Filter.h> // Filter library
|
||||
#include <AP_Buffer/AP_Buffer.h> // APM FIFO Buffer
|
||||
|
@ -798,6 +798,11 @@ void Plane::set_servos(void)
|
||||
*/
|
||||
void Plane::servos_output(void)
|
||||
{
|
||||
hal.rcout->cork();
|
||||
|
||||
// remap servo output to SERVO* ranges if enabled
|
||||
g2.servo_channels.remap_servo_output();
|
||||
|
||||
if (g.rudder_only == 0) {
|
||||
// when in RUDDER_ONLY mode we don't send the channel_roll
|
||||
// output and instead rely on KFF_RDDRMIX. That allows the yaw
|
||||
@ -808,5 +813,8 @@ void Plane::servos_output(void)
|
||||
channel_pitch->output();
|
||||
channel_throttle->output();
|
||||
channel_rudder->output();
|
||||
|
||||
RC_Channel_aux::output_ch_all();
|
||||
|
||||
hal.rcout->push();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user