Browse Source

add trial period

mission-4.1.18
yaozb 5 years ago
parent
commit
ecdc425ce8
  1. 46
      ArduCopter/AP_Arming.cpp
  2. 2
      ArduCopter/AP_Arming.h
  3. 4
      ArduCopter/Copter.h
  4. 5
      ArduCopter/Parameters.cpp
  5. 4
      ArduCopter/Parameters.h
  6. 17
      ArduCopter/system.cpp
  7. 7
      libraries/AP_GPS/AP_GPS.cpp
  8. 4
      libraries/AP_GPS/AP_GPS.h
  9. 1
      libraries/AP_GPS/GPS_Backend.cpp
  10. 2
      modules/mavlink

46
ArduCopter/AP_Arming.cpp

@ -52,6 +52,7 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure)
return mandatory_checks(display_failure); return mandatory_checks(display_failure);
} }
return fence_checks(display_failure) return fence_checks(display_failure)
& parameter_checks(display_failure) & parameter_checks(display_failure)
& motor_checks(display_failure) & motor_checks(display_failure)
@ -452,6 +453,28 @@ bool AP_Arming_Copter::proximity_checks(bool display_failure) const
return true; return true;
} }
bool AP_Arming_Copter::mandatory_deadline_checks(bool display_failure)
{
const AP_GPS &gps = AP::gps();
if(gps.status()<2)
return true;
if (!copter.deadline_ok())
{
//const AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf();
// const char *reason = ahrs.prearm_failure_reason();
int32_t deadline = 0;
copter.get_deadline_params(deadline);
// sprintf(temp,"time is up at %d-%d-%d ", deadline / 10000, (deadline % 10000) / 100, deadline % 100);
// reason = "Trial time has expired!";
// gcs().send_text(MAV_SEVERITY_INFO, "无法解锁,您的无人机授权已于%d-%d-%d到期", deadline / 10000, (deadline % 10000) / 100, deadline % 100);
check_failed(display_failure, "Trial time has expired at %d-%d-%d !", deadline / 10000, (deadline % 10000) / 100, deadline % 100);
return false;
}else{
return true;
}
}
// performs mandatory gps checks. returns true if passed // performs mandatory gps checks. returns true if passed
bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
{ {
@ -477,8 +500,10 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
#endif #endif
// return true if GPS is not required // return true if GPS is not required
if (!mode_requires_gps && !fence_requires_gps) { if (!mode_requires_gps && !fence_requires_gps)
return true; {
return mandatory_deadline_checks(display_failure);
// return true;
} }
// ensure GPS is ok // ensure GPS is ok
@ -494,6 +519,23 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
} }
check_failed(display_failure, "%s", reason); check_failed(display_failure, "%s", reason);
return false; return false;
}
else
{
return mandatory_deadline_checks(display_failure);
// if (!copter.deadline_ok())
// {
// const char *reason = ahrs.prearm_failure_reason();
// //char * temp =nullptr;
// int32_t deadline = 0;
// copter.get_deadline_params(deadline);
// // sprintf(temp,"time is up at %d-%d-%d ", deadline / 10000, (deadline % 10000) / 100, deadline % 100);
// reason ="Trial time has expired!";
// // gcs().send_text(MAV_SEVERITY_INFO, "无法解锁,您的无人机授权已于%d-%d-%d到期", deadline / 10000, (deadline % 10000) / 100, deadline % 100);
// check_failed(display_failure, "%s", reason);
// return false;
// }
} }
// check for GPS glitch (as reported by EKF) // check for GPS glitch (as reported by EKF)

2
ArduCopter/AP_Arming.h

@ -50,7 +50,7 @@ protected:
bool pilot_throttle_checks(bool display_failure); bool pilot_throttle_checks(bool display_failure);
bool oa_checks(bool display_failure); bool oa_checks(bool display_failure);
bool mandatory_gps_checks(bool display_failure); bool mandatory_gps_checks(bool display_failure);
bool mandatory_deadline_checks(bool display_failure);
void set_pre_arm_check(bool b); void set_pre_arm_check(bool b);
private: private:

4
ArduCopter/Copter.h

@ -837,7 +837,7 @@ private:
void convert_lgr_parameters(void); void convert_lgr_parameters(void);
void convert_tradheli_parameters(void); void convert_tradheli_parameters(void);
void convert_fs_options_params(void); void convert_fs_options_params(void);
void get_deadline_params( int32_t &deadline );
// precision_landing.cpp // precision_landing.cpp
void init_precland(); void init_precland();
void update_precland(); void update_precland();
@ -895,7 +895,7 @@ private:
const char* get_frame_string(); const char* get_frame_string();
void allocate_motors(void); void allocate_motors(void);
bool is_tradheli() const; bool is_tradheli() const;
bool deadline_ok();
// terrain.cpp // terrain.cpp
void terrain_update(); void terrain_update();
void terrain_logging(); void terrain_logging();

5
ArduCopter/Parameters.cpp

@ -76,6 +76,8 @@ const AP_Param::Info Copter::var_info[] = {
// @User: Advanced // @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255), GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),
GSCALAR(sysid_dead_line, "SYSID_DEADLINE", 401221),
// @Param: PILOT_THR_FILT // @Param: PILOT_THR_FILT
// @DisplayName: Throttle filter cutoff // @DisplayName: Throttle filter cutoff
// @Description: Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable // @Description: Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable
@ -1636,3 +1638,6 @@ const char* Copter::get_sysid_board_id(void)
snprintf(buf, sizeof(buf), "Version: zr-v4.0 ,Board ID: ZRZK.%5s%d",name,(int)g.sysid_board_id); snprintf(buf, sizeof(buf), "Version: zr-v4.0 ,Board ID: ZRZK.%5s%d",name,(int)g.sysid_board_id);
return buf; return buf;
} }
void Copter::get_deadline_params(int32_t &deadline ){
deadline = 20000000+ g.sysid_dead_line;
}

4
ArduCopter/Parameters.h

@ -376,7 +376,7 @@ public:
k_param_logger = 253, // 253 - Logging Group k_param_logger = 253, // 253 - Logging Group
// 254,255: reserved // 254,255: reserved
k_param_sysid_dead_line = 300,
// the k_param_* space is 9-bits in size // the k_param_* space is 9-bits in size
// 511: reserved // 511: reserved
}; };
@ -393,6 +393,8 @@ public:
AP_Int16 sysid_my_gcs; AP_Int16 sysid_my_gcs;
AP_Int8 telem_delay; AP_Int8 telem_delay;
AP_Int32 sysid_dead_line;
AP_Float throttle_filt; AP_Float throttle_filt;
AP_Int16 throttle_behavior; AP_Int16 throttle_behavior;
AP_Float pilot_takeoff_alt; AP_Float pilot_takeoff_alt;

17
ArduCopter/system.cpp

@ -333,6 +333,23 @@ bool Copter::position_ok() const
return (ekf_position_ok() || optflow_position_ok()); return (ekf_position_ok() || optflow_position_ok());
} }
bool Copter::deadline_ok()
{
int32_t deadline =0;
copter.get_deadline_params(deadline);
int32_t gps_date =0;
AP::gps().get_gps_headline_value(gps_date);
if ((deadline - gps_date) > 0)
{
return true;
}
else
{
return false;
}
}
// ekf_position_ok - returns true if the ekf claims it's horizontal absolute position estimate is ok and home position is set // ekf_position_ok - returns true if the ekf claims it's horizontal absolute position estimate is ok and home position is set
bool Copter::ekf_position_ok() const bool Copter::ekf_position_ok() const
{ {

7
libraries/AP_GPS/AP_GPS.cpp

@ -1179,6 +1179,11 @@ void AP_GPS::Write_AP_Logger_Log_Startup_messages()
} }
} }
void AP_GPS::get_gps_headline_value(int32_t & gps_date_time){
gps_date_time = state[GPS_BLENDED_INSTANCE].zr_date_timestamp;
}
/* /*
return the expected lag (in seconds) in the position and velocity readings from the gps return the expected lag (in seconds) in the position and velocity readings from the gps
return true if the GPS hardware configuration is known or the delay parameter has been set return true if the GPS hardware configuration is known or the delay parameter has been set
@ -1595,6 +1600,7 @@ void AP_GPS::calc_blended_state(void)
// use data from highest weighted sensor // use data from highest weighted sensor
state[GPS_BLENDED_INSTANCE].time_week = state[best_index].time_week; state[GPS_BLENDED_INSTANCE].time_week = state[best_index].time_week;
state[GPS_BLENDED_INSTANCE].time_week_ms = state[best_index].time_week_ms; state[GPS_BLENDED_INSTANCE].time_week_ms = state[best_index].time_week_ms;
state[GPS_BLENDED_INSTANCE].zr_date_timestamp = state[best_index].zr_date_timestamp;
} else { } else {
// use week number from highest weighting GPS (they should all have the same week number) // use week number from highest weighting GPS (they should all have the same week number)
state[GPS_BLENDED_INSTANCE].time_week = state[best_index].time_week; state[GPS_BLENDED_INSTANCE].time_week = state[best_index].time_week;
@ -1606,6 +1612,7 @@ void AP_GPS::calc_blended_state(void)
} }
} }
state[GPS_BLENDED_INSTANCE].time_week_ms = (uint32_t)temp_time_0; state[GPS_BLENDED_INSTANCE].time_week_ms = (uint32_t)temp_time_0;
state[GPS_BLENDED_INSTANCE].zr_date_timestamp = state[best_index].zr_date_timestamp;
} }
// calculate a blended value for the timing data and lag // calculate a blended value for the timing data and lag

4
libraries/AP_GPS/AP_GPS.h

@ -154,7 +154,7 @@ public:
bool have_gps_yaw_accuracy; ///< does the GPS give a heading accuracy estimate? Set to true only once available bool have_gps_yaw_accuracy; ///< does the GPS give a heading accuracy estimate? Set to true only once available
uint32_t last_gps_time_ms; ///< the system time we got the last GPS timestamp, milliseconds uint32_t last_gps_time_ms; ///< the system time we got the last GPS timestamp, milliseconds
uint32_t uart_timestamp_ms; ///< optional timestamp from set_uart_timestamp() uint32_t uart_timestamp_ms; ///< optional timestamp from set_uart_timestamp()
uint32_t zr_date_timestamp; //2020-03-26 = 20200326
// all the following fields must only all be filled by RTK capable backend drivers // all the following fields must only all be filled by RTK capable backend drivers
uint32_t rtk_time_week_ms; ///< GPS Time of Week of last baseline in milliseconds uint32_t rtk_time_week_ms; ///< GPS Time of Week of last baseline in milliseconds
uint16_t rtk_week_number; ///< GPS Week Number of last baseline uint16_t rtk_week_number; ///< GPS Week Number of last baseline
@ -438,7 +438,7 @@ public:
// handle possibly fragmented RTCM injection data // handle possibly fragmented RTCM injection data
void handle_gps_rtcm_fragment(uint8_t flags, const uint8_t *data, uint8_t len); void handle_gps_rtcm_fragment(uint8_t flags, const uint8_t *data, uint8_t len);
void get_gps_headline_value(int32_t & gps_date_time);
protected: protected:
// configuration parameters // configuration parameters

1
libraries/AP_GPS/GPS_Backend.cpp

@ -94,6 +94,7 @@ void AP_GPS_Backend::make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds)
rmon += 12; rmon += 12;
year -= 1; year -= 1;
} }
state.zr_date_timestamp =(year+2000)*10000+mon*100+day; //FIXME only calcute onecs
// get time in seconds since unix epoch // get time in seconds since unix epoch
uint32_t ret = (year/4) - (GPS_LEAPSECONDS_MILLIS / 1000UL) + 367*rmon/12 + day; uint32_t ret = (year/4) - (GPS_LEAPSECONDS_MILLIS / 1000UL) + 367*rmon/12 + day;

2
modules/mavlink

@ -1 +1 @@
Subproject commit d2cc7dbff67f8c318a40e1ef57a99488b4737fab Subproject commit ff8ada062c96f04dc830e54b657aca4430408433
Loading…
Cancel
Save