mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Mount: Use AP_Gimbal on the AP_Mount_MAVLink class
This commit is contained in:
parent
ee8c92c850
commit
b3dd8891c8
@ -3,6 +3,8 @@
|
||||
#include <AP_Mount_MAVLink.h>
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <stdio.h>
|
||||
#include <AP_Gimbal.h>
|
||||
|
||||
#if MOUNT_DEBUG
|
||||
#include <stdio.h>
|
||||
@ -10,7 +12,8 @@
|
||||
|
||||
AP_Mount_MAVLink::AP_Mount_MAVLink(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance) :
|
||||
AP_Mount_Backend(frontend, state, instance),
|
||||
_initialised(false)
|
||||
_initialised(false),
|
||||
_gimbal(frontend._ahrs, 1, MAV_COMP_ID_GIMBAL)
|
||||
{}
|
||||
|
||||
// init - performs any required initialisation for this instance
|
||||
@ -92,6 +95,8 @@ void AP_Mount_MAVLink::status_msg(mavlink_channel_t chan)
|
||||
*/
|
||||
void AP_Mount_MAVLink::handle_gimbal_report(mavlink_channel_t chan, mavlink_message_t *msg)
|
||||
{
|
||||
_gimbal._angle_ef_target_rad = _angle_ef_target_rad;
|
||||
_gimbal.receive_feedback(chan,msg);
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -17,7 +17,7 @@
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <RC_Channel.h>
|
||||
#include <AP_Mount_Backend.h>
|
||||
#include <AP_SmallEKF.h>
|
||||
#include <AP_Gimbal.h>
|
||||
|
||||
class AP_Mount_MAVLink : public AP_Mount_Backend
|
||||
{
|
||||
@ -50,6 +50,8 @@ public:
|
||||
private:
|
||||
// internal variables
|
||||
bool _initialised; // true once the driver has been initialised
|
||||
|
||||
AP_Gimbal _gimbal;
|
||||
};
|
||||
|
||||
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
||||
|
Loading…
Reference in New Issue
Block a user