mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
GCS_MAVLink: send_autopilot_version accepts version
This commit is contained in:
parent
debbecf355
commit
f4acc79fce
@ -148,7 +148,7 @@ public:
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
void send_opticalflow(AP_AHRS_NavEKF &ahrs, const OpticalFlow &optflow);
|
||||
#endif
|
||||
void send_autopilot_version() const;
|
||||
void send_autopilot_version(uint8_t major_version = 0, uint8_t minor_version = 0, uint8_t patch_version = 0, enum FIRMWARE_VERSION_TYPE version_type = FIRMWARE_VERSION_TYPE_DEV) const;
|
||||
void send_local_position(const AP_AHRS &ahrs) const;
|
||||
void send_vibration(const AP_InertialSensor &ins) const;
|
||||
|
||||
|
@ -1262,7 +1262,7 @@ void GCS_MAVLINK::send_opticalflow(AP_AHRS_NavEKF &ahrs, const OpticalFlow &optf
|
||||
/*
|
||||
send AUTOPILOT_VERSION packet
|
||||
*/
|
||||
void GCS_MAVLINK::send_autopilot_version() const
|
||||
void GCS_MAVLINK::send_autopilot_version(uint8_t major_version, uint8_t minor_version, uint8_t patch_version, enum FIRMWARE_VERSION_TYPE version_type) const
|
||||
{
|
||||
uint32_t flight_sw_version = 0;
|
||||
uint32_t middleware_sw_version = 0;
|
||||
@ -1275,6 +1275,11 @@ void GCS_MAVLINK::send_autopilot_version() const
|
||||
uint16_t product_id = 0;
|
||||
uint64_t uid = 0;
|
||||
|
||||
flight_sw_version = major_version << (8*3) | \
|
||||
minor_version << (8*2) | \
|
||||
patch_version << (8*1) | \
|
||||
version_type << (8*0);
|
||||
|
||||
#if defined(GIT_VERSION)
|
||||
strncpy((char *)flight_custom_version, GIT_VERSION, 8);
|
||||
#else
|
||||
@ -1352,4 +1357,3 @@ void GCS_MAVLINK::send_vibration(const AP_InertialSensor &ins) const
|
||||
ins.get_accel_clip_count(2));
|
||||
#endif
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user