diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index 6d37ade993..3d429e053d 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -419,9 +419,9 @@ void AP_Mount::init(DataFlash_Class *dataflash, const AP_SerialManager& serial_m // default mount to servo mount if rc output channels to control roll, tilt or pan have been defined if (!state[0]._type.configured()) { - if (RC_Channel_aux::function_assigned(RC_Channel_aux::Aux_servo_function_t::k_mount_pan) || - RC_Channel_aux::function_assigned(RC_Channel_aux::Aux_servo_function_t::k_mount_tilt) || - RC_Channel_aux::function_assigned(RC_Channel_aux::Aux_servo_function_t::k_mount_roll)) { + if (SRV_Channels::function_assigned(SRV_Channel::Aux_servo_function_t::k_mount_pan) || + SRV_Channels::function_assigned(SRV_Channel::Aux_servo_function_t::k_mount_tilt) || + SRV_Channels::function_assigned(SRV_Channel::Aux_servo_function_t::k_mount_roll)) { state[0]._type.set_and_save(Mount_Type_Servo); } } diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index 1394cc0d4a..81a1b221d0 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -83,7 +83,7 @@ void AP_Mount_Backend::control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_ // update_targets_from_rc - updates angle targets using input from receiver void AP_Mount_Backend::update_targets_from_rc() { -#define rc_ch(i) RC_Channel::rc_channel(i-1) +#define rc_ch(i) RC_Channels::rc_channel(i-1) uint8_t roll_rc_in = _state._roll_rc_in; uint8_t tilt_rc_in = _state._tilt_rc_in; diff --git a/libraries/AP_Mount/AP_Mount_Servo.cpp b/libraries/AP_Mount/AP_Mount_Servo.cpp index 02a467b644..0332c47adb 100644 --- a/libraries/AP_Mount/AP_Mount_Servo.cpp +++ b/libraries/AP_Mount/AP_Mount_Servo.cpp @@ -6,16 +6,16 @@ extern const AP_HAL::HAL& hal; void AP_Mount_Servo::init(const AP_SerialManager& serial_manager) { if (_instance == 0) { - _roll_idx = RC_Channel_aux::k_mount_roll; - _tilt_idx = RC_Channel_aux::k_mount_tilt; - _pan_idx = RC_Channel_aux::k_mount_pan; - _open_idx = RC_Channel_aux::k_mount_open; + _roll_idx = SRV_Channel::k_mount_roll; + _tilt_idx = SRV_Channel::k_mount_tilt; + _pan_idx = SRV_Channel::k_mount_pan; + _open_idx = SRV_Channel::k_mount_open; } else { // this must be the 2nd mount - _roll_idx = RC_Channel_aux::k_mount2_roll; - _tilt_idx = RC_Channel_aux::k_mount2_tilt; - _pan_idx = RC_Channel_aux::k_mount2_pan; - _open_idx = RC_Channel_aux::k_mount2_open; + _roll_idx = SRV_Channel::k_mount2_roll; + _tilt_idx = SRV_Channel::k_mount2_tilt; + _pan_idx = SRV_Channel::k_mount2_pan; + _open_idx = SRV_Channel::k_mount2_open; } // check which servos have been assigned @@ -107,9 +107,9 @@ void AP_Mount_Servo::set_mode(enum MAV_MOUNT_MODE mode) // should be called periodically (i.e. 1hz or less) void AP_Mount_Servo::check_servo_map() { - _flags.roll_control = RC_Channel_aux::function_assigned(_roll_idx); - _flags.tilt_control = RC_Channel_aux::function_assigned(_tilt_idx); - _flags.pan_control = RC_Channel_aux::function_assigned(_pan_idx); + _flags.roll_control = SRV_Channels::function_assigned(_roll_idx); + _flags.tilt_control = SRV_Channels::function_assigned(_tilt_idx); + _flags.pan_control = SRV_Channels::function_assigned(_pan_idx); } // status_msg - called to allow mounts to send their status to GCS using the MOUNT_STATUS message @@ -197,5 +197,5 @@ void AP_Mount_Servo::move_servo(uint8_t function_idx, int16_t angle, int16_t ang { // saturate to the closest angle limit if outside of [min max] angle interval int16_t servo_out = closest_limit(angle, angle_min, angle_max); - RC_Channel_aux::move_servo((RC_Channel_aux::Aux_servo_function_t)function_idx, servo_out, angle_min, angle_max); + SRV_Channels::move_servo((SRV_Channel::Aux_servo_function_t)function_idx, servo_out, angle_min, angle_max); } diff --git a/libraries/AP_Mount/AP_Mount_Servo.h b/libraries/AP_Mount/AP_Mount_Servo.h index ffd8818d13..8f9cf28a05 100644 --- a/libraries/AP_Mount/AP_Mount_Servo.h +++ b/libraries/AP_Mount/AP_Mount_Servo.h @@ -8,7 +8,7 @@ #include #include #include -#include +#include #include "AP_Mount_Backend.h" class AP_Mount_Servo : public AP_Mount_Backend @@ -17,10 +17,10 @@ public: // Constructor AP_Mount_Servo(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance): AP_Mount_Backend(frontend, state, instance), - _roll_idx(RC_Channel_aux::k_none), - _tilt_idx(RC_Channel_aux::k_none), - _pan_idx(RC_Channel_aux::k_none), - _open_idx(RC_Channel_aux::k_none), + _roll_idx(SRV_Channel::k_none), + _tilt_idx(SRV_Channel::k_none), + _pan_idx(SRV_Channel::k_none), + _open_idx(SRV_Channel::k_none), _last_check_servo_map_ms(0) { // init to no axis being controlled @@ -53,7 +53,7 @@ private: bool pan_control :1; // true if mount has pan control } _flags; - // check_servo_map - detects which axis we control (i.e. _flags) using the functions assigned to the servos in the RC_Channel_aux + // check_servo_map - detects which axis we control (i.e. _flags) using the functions assigned to the servos in the SRV_Channel // should be called periodically (i.e. 1hz or less) void check_servo_map(); @@ -66,11 +66,11 @@ private: /// move_servo - moves servo with the given id to the specified angle. all angles are in degrees * 10 void move_servo(uint8_t rc, int16_t angle, int16_t angle_min, int16_t angle_max); - // RC_Channel_aux - different id numbers are used depending upon the instance number - RC_Channel_aux::Aux_servo_function_t _roll_idx; // RC_Channel_aux mount roll function index - RC_Channel_aux::Aux_servo_function_t _tilt_idx; // RC_Channel_aux mount tilt function index - RC_Channel_aux::Aux_servo_function_t _pan_idx; // RC_Channel_aux mount pan function index - RC_Channel_aux::Aux_servo_function_t _open_idx; // RC_Channel_aux mount open function index + // SRV_Channel - different id numbers are used depending upon the instance number + SRV_Channel::Aux_servo_function_t _roll_idx; // SRV_Channel mount roll function index + SRV_Channel::Aux_servo_function_t _tilt_idx; // SRV_Channel mount tilt function index + SRV_Channel::Aux_servo_function_t _pan_idx; // SRV_Channel mount pan function index + SRV_Channel::Aux_servo_function_t _open_idx; // SRV_Channel mount open function index Vector3f _angle_bf_output_deg; // final body frame output angle in degrees