mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: added sending of attitude and velocity for SIYI
will be used by SIYI for improved gimbal control
This commit is contained in:
parent
0db1719c8f
commit
691b23db7d
|
@ -82,6 +82,12 @@ void AP_Mount_Siyi::update()
|
|||
_last_rangefinder_req_ms = now_ms;
|
||||
}
|
||||
|
||||
// send attitude to gimbal at 10Hz
|
||||
if (now_ms - _last_attitude_send_ms > 100) {
|
||||
_last_attitude_send_ms = now_ms;
|
||||
send_attitude();
|
||||
}
|
||||
|
||||
// run zoom control
|
||||
update_zoom_control();
|
||||
|
||||
|
@ -1087,4 +1093,31 @@ void AP_Mount_Siyi::check_firmware_version() const
|
|||
}
|
||||
}
|
||||
|
||||
/*
|
||||
send ArduPilot attitude to gimbal
|
||||
*/
|
||||
void AP_Mount_Siyi::send_attitude(void)
|
||||
{
|
||||
const auto &ahrs = AP::ahrs();
|
||||
struct {
|
||||
uint32_t time_boot_ms;
|
||||
float roll, pitch, yaw;
|
||||
float rollspeed, pitchspeed, yawspeed;
|
||||
} attitude;
|
||||
|
||||
// get attitude as euler 321
|
||||
const auto &gyro = ahrs.get_gyro();
|
||||
const uint32_t now_ms = AP_HAL::millis();
|
||||
|
||||
attitude.time_boot_ms = now_ms;
|
||||
attitude.roll = ahrs.roll;
|
||||
attitude.pitch = ahrs.pitch;
|
||||
attitude.yaw = ahrs.yaw;
|
||||
attitude.rollspeed = gyro.x;
|
||||
attitude.pitchspeed = gyro.y;
|
||||
attitude.yawspeed = gyro.z;
|
||||
|
||||
send_packet(SiyiCommandId::EXTERNAL_ATTITUDE, (const uint8_t *)&attitude, sizeof(attitude));
|
||||
}
|
||||
|
||||
#endif // HAL_MOUNT_SIYI_ENABLED
|
||||
|
|
|
@ -111,6 +111,7 @@ private:
|
|||
ABSOLUTE_ZOOM = 0x0F,
|
||||
SET_CAMERA_IMAGE_TYPE = 0x11,
|
||||
READ_RANGEFINDER = 0x15,
|
||||
EXTERNAL_ATTITUDE = 0x22,
|
||||
};
|
||||
|
||||
// Function Feedback Info packet info_type values
|
||||
|
@ -324,6 +325,10 @@ private:
|
|||
uint32_t _last_rangefinder_dist_ms; // system time of last successful read of rangefinder distance
|
||||
float _rangefinder_dist_m; // distance received from rangefinder
|
||||
|
||||
// sending of attitude to gimbal
|
||||
uint32_t _last_attitude_send_ms;
|
||||
void send_attitude(void);
|
||||
|
||||
// hardware lookup table indexed by HardwareModel enum values (see above)
|
||||
struct HWInfo {
|
||||
uint8_t hwid[2];
|
||||
|
|
Loading…
Reference in New Issue