mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: add devid parameter and setter
This commit is contained in:
parent
b0de3b57bf
commit
2a30bc7ce1
|
@ -14,6 +14,12 @@ void AP_Mount_Backend::init()
|
|||
_target_sysid = _params.sysid_default.get();
|
||||
}
|
||||
|
||||
// set device id of this instance, for MNTx_DEVID parameter
|
||||
void AP_Mount_Backend::set_dev_id(uint32_t id)
|
||||
{
|
||||
_params.dev_id.set_and_save(int32_t(id));
|
||||
}
|
||||
|
||||
// return true if this mount accepts roll targets
|
||||
bool AP_Mount_Backend::has_roll_control() const
|
||||
{
|
||||
|
|
|
@ -43,6 +43,9 @@ public:
|
|||
// init - performs any required initialisation for this instance
|
||||
virtual void init();
|
||||
|
||||
// set device id of this instance, for MNTx_DEVID parameter
|
||||
void set_dev_id(uint32_t id);
|
||||
|
||||
// update mount position - should be called periodically
|
||||
virtual void update() = 0;
|
||||
|
||||
|
|
|
@ -158,6 +158,14 @@ const AP_Param::GroupInfo AP_Mount_Params::var_info[] = {
|
|||
// @RebootRequired: True
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_SYSID_DFLT", 14, AP_Mount_Params, sysid_default, 0),
|
||||
|
||||
// @Param: _DEVID
|
||||
// @DisplayName: Mount Device ID
|
||||
// @Description: Mount device ID, taking into account its type, bus and instance
|
||||
// @ReadOnly: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO_FLAGS("_DEVID", 15, AP_Mount_Params, dev_id, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -30,4 +30,5 @@ public:
|
|||
AP_Float roll_stb_lead; // roll lead control gain (only used by servo backend)
|
||||
AP_Float pitch_stb_lead; // pitch lead control gain (only used by servo backend)
|
||||
AP_Int8 sysid_default; // target sysid for mount to follow
|
||||
AP_Int32 dev_id; // Device id taking into account bus
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue