AP_Mount: SToRM32 minor comment fix
also move definitions to cpp file
This commit is contained in:
parent
e0ce8035b9
commit
b6d7601a55
@ -5,6 +5,9 @@
|
|||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
#define AP_MOUNT_STORM32_RESEND_MS 1000 // resend angle targets to gimbal once per second
|
||||||
|
#define AP_MOUNT_STORM32_SEARCH_MS 60000 // search for gimbal for 1 minute after startup
|
||||||
|
|
||||||
AP_Mount_SToRM32::AP_Mount_SToRM32(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance) :
|
AP_Mount_SToRM32::AP_Mount_SToRM32(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance) :
|
||||||
AP_Mount_Backend(frontend, state, instance),
|
AP_Mount_Backend(frontend, state, instance),
|
||||||
_chan(MAVLINK_COMM_0)
|
_chan(MAVLINK_COMM_0)
|
||||||
|
@ -12,9 +12,6 @@
|
|||||||
#include <RC_Channel/RC_Channel.h>
|
#include <RC_Channel/RC_Channel.h>
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
|
|
||||||
#define AP_MOUNT_STORM32_RESEND_MS 1000 // resend angle targets to gimbal once per second
|
|
||||||
#define AP_MOUNT_STORM32_SEARCH_MS 60000 // search for gimbal for 1 minute after startup
|
|
||||||
|
|
||||||
class AP_Mount_SToRM32 : public AP_Mount_Backend
|
class AP_Mount_SToRM32 : public AP_Mount_Backend
|
||||||
{
|
{
|
||||||
|
|
||||||
@ -49,7 +46,7 @@ private:
|
|||||||
bool _initialised; // true once the driver has been initialised
|
bool _initialised; // true once the driver has been initialised
|
||||||
uint8_t _sysid; // sysid of gimbal
|
uint8_t _sysid; // sysid of gimbal
|
||||||
uint8_t _compid; // component id of gimbal
|
uint8_t _compid; // component id of gimbal
|
||||||
mavlink_channel_t _chan; // mavlink channel used to communicate with gimbal. Currently hard-coded to Telem2
|
mavlink_channel_t _chan; // mavlink channel used to communicate with gimbal
|
||||||
uint32_t _last_send; // system time of last do_mount_control sent to gimbal
|
uint32_t _last_send; // system time of last do_mount_control sent to gimbal
|
||||||
};
|
};
|
||||||
#endif // HAL_MOUNT_ENABLED
|
#endif // HAL_MOUNT_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user