Browse Source

测流起始航点修改,增加参数调整

celiu-4.0.17-rc8
zbr 4 years ago
parent
commit
334eb0ae05
  1. 8
      ArduCopter/Parameters.cpp
  2. 2
      ArduCopter/mode_auto.cpp
  3. 6
      ArduCopter/version.h
  4. 1
      libraries/AC_WPNav/AC_WPNav.cpp
  5. 2
      libraries/AC_WPNav/AC_WPNav.h

8
ArduCopter/Parameters.cpp

@ -1668,16 +1668,16 @@ const char* Copter::get_sysid_board_id(void) @@ -1668,16 +1668,16 @@ const char* Copter::get_sysid_board_id(void)
switch (type)
{
case 0:
snprintf(buf, sizeof(buf), "Version: zr-v4.1.2 ,ID: RS100%04d%05d",(int)nameValue1,(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: zr-v4.1.3 ,ID: RS100%04d%05d",(int)nameValue1,(int)nameValue2);
break;
case 1:
snprintf(buf, sizeof(buf), "Version: zr-v4.1.2 ,ID: M660%04d%05d",(int)nameValue1,(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: zr-v4.1.3 ,ID: M660%04d%05d",(int)nameValue1,(int)nameValue2);
break;
case 2:
snprintf(buf, sizeof(buf), "Version: zr-v4.1.2 ,ID: RF610%04d%05d",(int)nameValue1,(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: zr-v4.1.3 ,ID: RF610%04d%05d",(int)nameValue1,(int)nameValue2);
break;
case 3:
snprintf(buf, sizeof(buf), "Version: zr-v4.1.2 ,Board ID: ZRZK.20QT2.%d",(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: zr-v4.1.3 ,Board ID: ZRZK.20QT2.%d",(int)nameValue2);
break;
default:

2
ArduCopter/mode_auto.cpp

@ -1889,7 +1889,7 @@ bool ModeAuto::verify_nav_wp_flow_measure(const AP_Mission::Mission_Command& cmd @@ -1889,7 +1889,7 @@ bool ModeAuto::verify_nav_wp_flow_measure(const AP_Mission::Mission_Command& cmd
return false;
}
copter.flow_measure.set_wp_index(cmd.index -1);
copter.flow_measure.set_wp_index(cmd.index - copter.wp_nav->get_index_start()); // 修正测流起始航点
copter.flow_measure.set_reach_flow_wp(true); //到达航点标志置1
if(copter.flow_measure.get_flow_update_state() < 2)
return false;

6
ArduCopter/version.h

@ -6,12 +6,12 @@ @@ -6,12 +6,12 @@
#include "ap_version.h"
#define THISFIRMWARE "ZRUAV v4.1.2" //"ArduCopter V4.0.0"
#define THISFIRMWARE "ZRUAV v4.1.3" //"ArduCopter V4.0.0"
// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,1,2,FIRMWARE_VERSION_TYPE_OFFICIAL
#define FIRMWARE_VERSION 4,1,3,FIRMWARE_VERSION_TYPE_OFFICIAL
#define FW_MAJOR 4
#define FW_MINOR 1
#define FW_PATCH 2
#define FW_PATCH 3
#define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL

1
libraries/AC_WPNav/AC_WPNav.cpp

@ -76,6 +76,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] = { @@ -76,6 +76,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] = {
AP_GROUPINFO("DELAY_TIME", 12, AC_WPNav, _measure_delay_time, 10),
AP_GROUPINFO("INDEX_STR", 13, AC_WPNav, _measure_index_start, 2),
AP_GROUPEND
};

2
libraries/AC_WPNav/AC_WPNav.h

@ -225,6 +225,7 @@ public: @@ -225,6 +225,7 @@ public:
bool get_fast_waypoint() const { return _fast_wp; }
uint8_t get_measure_time(void){return (uint8_t)_measure_delay_time;};
uint8_t get_index_start(void){return (uint8_t)_measure_index_start;};
protected:
@ -322,4 +323,5 @@ protected: @@ -322,4 +323,5 @@ protected:
AP_Int8 _fast_wp; //modify by @Brown
AP_Int8 _measure_delay_time; //modify by @Brown
AP_Int8 _measure_index_start;
};

Loading…
Cancel
Save