Skip to content

Commit

Permalink
AP_Mount: Update Tusuav backend 11.15
Browse files Browse the repository at this point in the history
All reviews have been addressed. 11.15
  • Loading branch information
yi committed Nov 15, 2024
1 parent 9db4550 commit a5b4e3a
Showing 1 changed file with 8 additions and 11 deletions.
19 changes: 8 additions & 11 deletions libraries/AP_Mount/AP_Mount_Tusuav.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,9 @@

#pragma once

#include "AP_Mount_Backend_Serial.h"

#include "AP_Mount_config.h"
#if HAL_MOUNT_TUSUAV_ENABLED
#include "AP_Mount_Backend_Serial.h"

#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
Expand All @@ -45,9 +45,6 @@ class AP_Mount_Tusuav : public AP_Mount_Backend_Serial
/* Do not allow copies */
CLASS_NO_COPY(AP_Mount_Tusuav);

// // init - performs any required initialisation for this instance
// void init() override;

// update mount position - should be called periodically
void update() override;

Expand Down Expand Up @@ -98,6 +95,7 @@ class AP_Mount_Tusuav : public AP_Mount_Backend_Serial

// get attitude as a quaternion. returns true on success
bool get_attitude_quaternion(Quaternion& att_quat) override;

private:

// send text prefix string to reduce flash cost
Expand Down Expand Up @@ -205,7 +203,7 @@ class AP_Mount_Tusuav : public AP_Mount_Backend_Serial
struct ParsedRxMsg {
struct FrameType msg; // the parsed message
ParseState state; // the current state of the message parser
}_parsed_msg;
} _parsed_msg;

union PodCtrlUnion {
struct PodCtrlBitField {
Expand Down Expand Up @@ -292,7 +290,7 @@ class AP_Mount_Tusuav : public AP_Mount_Backend_Serial
uint8_t no_define1:1;
} bits;
uint8_t all;
}fc_status;
} fc_status;
float fc_gyro[3]; // fc body frame NED angular speed in degrees/sec
float fc_acc[3]; // fc body frame NED acceleration in G (9.8m/s^2)
float vel[3]; // fc earth coordinate NED velocity in m/s
Expand All @@ -301,7 +299,6 @@ class AP_Mount_Tusuav : public AP_Mount_Backend_Serial
float altitude;
float longitude;
float latitude;

};

//GimbalSubCmd_PlaneSensor_Attitude data frame
Expand All @@ -316,9 +313,9 @@ class AP_Mount_Tusuav : public AP_Mount_Backend_Serial
}time;

struct PACKED LocType {
int32_t lat; // latitude
int32_t lat; // latitude *1e7
int32_t lng; // longitude
int32_t altitude_cm; // altitude
int32_t altitude_cm; // altitude (cm)
uint32_t time_of_week_ms; // GPS time of the week
} loc;

Expand Down Expand Up @@ -355,7 +352,7 @@ class AP_Mount_Tusuav : public AP_Mount_Backend_Serial

// send packet to gimbal
// returns true on success, false if outgoing serial buffer is full
bool send_packet(struct FrameType frame);
bool send_packet(const FrameType& frame);

// send handshake, gimbal will respond with T1_F1_B1_D1 packet that includes current angles
void send_time_sync();
Expand Down

0 comments on commit a5b4e3a

Please sign in to comment.