Browse Source

mark zr4.0.5 ,0908

celiu-4.0.17-rc8
zbr3550 4 years ago
parent
commit
10a4d38b8b
  1. 3
      ArduCopter/Copter.h
  2. 2
      ArduCopter/mode_auto.cpp
  3. 2
      ArduCopter/version.h
  4. 16
      ArduCopter/zr_flight.cpp
  5. 3
      libraries/AC_WPNav/AC_WPNav.h
  6. 2
      modules/mavlink

3
ArduCopter/Copter.h

@ -701,7 +701,8 @@ private: @@ -701,7 +701,8 @@ private:
bool set_home_to_current_location(bool lock) WARN_IF_UNUSED;
bool set_home(const Location& loc, bool lock) WARN_IF_UNUSED;
bool far_from_EKF_origin(const Location& loc);
bool close_to_EKF_origin(const Location& loc);
// compassmot.cpp
MAV_RESULT mavlink_compassmot(const GCS_MAVLINK &gcs_chan);

2
ArduCopter/mode_auto.cpp

@ -1209,6 +1209,8 @@ void ModeAuto::do_nav_wp(const AP_Mission::Mission_Command& cmd) @@ -1209,6 +1209,8 @@ void ModeAuto::do_nav_wp(const AP_Mission::Mission_Command& cmd)
// for unsupported commands it is safer to stop
break;
}
fast_waypoint = copter.wp_nav->get_fast_waypoint();
copter.wp_nav->set_fast_waypoint(fast_waypoint);
}
}

2
ArduCopter/version.h

@ -6,7 +6,7 @@ @@ -6,7 +6,7 @@
#include "ap_version.h"
#define THISFIRMWARE "ZRUAV v4.0.5-rc1" //"ArduCopter V4.0.0"
#define THISFIRMWARE "ZRUAV v4.0.5-rc2" //"ArduCopter V4.0.0"
// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,0,5,FIRMWARE_VERSION_TYPE_OFFICIAL

16
ArduCopter/zr_flight.cpp

@ -5,7 +5,18 @@ @@ -5,7 +5,18 @@
void Copter::do_avoid_action(){
}
// bool Copter::close_to_EKF_origin(const Location& loc)
// {
// // check distance to EKF origin
// const struct Location &ekf_origin = inertial_nav.get_origin();
// if (get_distance(ekf_origin, loc) < 15 && ekf_origin.alt < 5000) {
// // gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: dist:%.2f,alt:%d",get_distance(ekf_origin, loc) ,ekf_origin.alt);
// return true;
// }
// // close enough to origin
// return false;
// }
bool Copter::zr_radio_valid(){
if(!motors->armed()){
@ -66,10 +77,7 @@ void Copter::zr_SuperSlowLoop(){ @@ -66,10 +77,7 @@ void Copter::zr_SuperSlowLoop(){
relay.off(3);
// rc().set_enable_ch();
updownStatus =UpDown_TakeOffStart;
mavlink_zr_flying_status_t zr_flying_status_t;
zr_flying_status_t.updown_status = updownStatus;
//TODO UPDATE COUNTDOWN
gcs().update_zr_fly_status(&zr_flying_status_t);
}
if(before_fly){
uint8_t cnt,cacl_volt_pst;

3
libraries/AC_WPNav/AC_WPNav.h

@ -223,7 +223,8 @@ public: @@ -223,7 +223,8 @@ public:
static const struct AP_Param::GroupInfo var_info[];
bool get_fast_waypoint(bool fast) { return _fast_wp; }
bool get_fast_waypoint() const { return _fast_wp; }
protected:

2
modules/mavlink

@ -1 +1 @@ @@ -1 +1 @@
Subproject commit 4a6577557847fcb13f8bd9b7ebbe54f4a5a9f00e
Subproject commit 18cab6950986cd7b9b7a507ec35f3501d4a7e019
Loading…
Cancel
Save