Mount: backends use reference to their state

This commit is contained in:
Randy Mackay 2015-01-19 10:39:55 +09:00 committed by Andrew Tridgell
parent bf82e82282
commit acbcf3c54e
3 changed files with 7 additions and 5 deletions

View File

@ -417,17 +417,17 @@ void AP_Mount::init()
// check for servo mounts
if (mount_type == Mount_Type_Servo) {
_backends[instance] = new AP_Mount_Servo(*this, instance);
_backends[instance] = new AP_Mount_Servo(*this, state[instance], instance);
_num_instances++;
// check for MAVLink mounts
} else if (mount_type == Mount_Type_MAVLink) {
_backends[instance] = new AP_Mount_MAVLink(*this, instance);
_backends[instance] = new AP_Mount_MAVLink(*this, state[instance], instance);
_num_instances++;
// check for Alexmos mounts
} else if (mount_type == Mount_Type_Alexmos) {
_backends[instance] = new AP_Mount_Alexmos(*this, instance);
_backends[instance] = new AP_Mount_Alexmos(*this, state[instance], instance);
_num_instances++;
}

View File

@ -108,7 +108,7 @@ public:
// parameter var table
static const struct AP_Param::GroupInfo var_info[];
private:
protected:
// private members
const AP_AHRS &_ahrs;

View File

@ -29,8 +29,9 @@ class AP_Mount_Backend
{
public:
// Constructor
AP_Mount_Backend(AP_Mount &frontend, uint8_t instance) :
AP_Mount_Backend(AP_Mount &frontend, AP_Mount::mount_state& state, uint8_t instance) :
_frontend(frontend),
_state(state),
_instance(instance)
{}
@ -74,6 +75,7 @@ protected:
void calc_angle_to_location(const struct Location &target, Vector3f& angles_to_target_rad, bool calc_tilt, bool calc_pan);
AP_Mount &_frontend; // reference to the front end which holds parameters
AP_Mount::mount_state &_state; // refernce to the parameters and state for this backend
uint8_t _instance; // this instance's number
Vector3f _angle_ef_target_rad; // desired earth-frame roll, tilt and pan angles in radians
};