Browse Source

编译条件调整,删除distance_sersor

zr-v5.1
Brown.Z 3 years ago
parent
commit
5c0057db86
  1. 7
      ArduCopter/AP_Arming.cpp
  2. 4
      Tools/ardupilotwaf/boards.py
  3. 23
      libraries/AP_UAVCAN/dsdl/zrzk/equipment/distance_sensor/26110.Proximity.uavcan

7
ArduCopter/AP_Arming.cpp

@ -952,15 +952,16 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che @@ -952,15 +952,16 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che
return true;
}
/**
* @brief ZR
*/
bool AP_Arming_Copter::mandatory_deadline_checks(bool display_failure)
{
uint32_t date;
if (!copter.zr_app.check_deadline(date))
{
// check_failed(true, "无法解锁,授权于 %u-%u-%u 到期!", date / 10000, (date % 10000) / 100, date % 100);
check_failed(true, "Trial time has expired at %lu-%lu-%lu", date / 10000, (date % 10000) / 100, date % 100);
// check_failed(display_failure, "Trial time has expired at %d-%d-%d !", date / 10000, (date % 10000) / 100, date % 100);
check_failed(display_failure, "Authorization expires:%lu-%lu-%lu", date / 10000, (date % 10000) / 100, date % 100);
return false;
}else{
return true;

4
Tools/ardupilotwaf/boards.py

@ -108,7 +108,7 @@ class Board: @@ -108,7 +108,7 @@ class Board:
'-Wall',
'-Wextra',
'-Werror=format',
# '-Werror=format',
'-Wpointer-arith',
'-Wcast-align',
'-Wno-missing-field-initializers',
@ -211,7 +211,7 @@ class Board: @@ -211,7 +211,7 @@ class Board:
'-Werror=format-security',
'-Werror=format-extra-args',
'-Werror=enum-compare',
'-Werror=format',
# '-Werror=format',
'-Werror=array-bounds',
'-Werror=uninitialized',
'-Werror=init-self',

23
libraries/AP_UAVCAN/dsdl/zrzk/equipment/distance_sensor/26110.Proximity.uavcan

@ -1,23 +0,0 @@ @@ -1,23 +0,0 @@
uint8 sensor_id
uint5 SENSOR_TYPE_UNDEFINED = 0
uint5 SENSOR_TYPE_SONAR = 1
uint5 SENSOR_TYPE_LIDAR = 2
uint5 SENSOR_TYPE_RADAR = 3
uint5 sensor_type
uint3 READING_TYPE_UNDEFINED = 0 # Range is unknown
uint3 READING_TYPE_VALID_RANGE = 1 # Range field contains valid distance
uint3 READING_TYPE_TOO_CLOSE = 2 # Range field contains min range for the sensor
uint3 READING_TYPE_TOO_FAR = 3 # Range field contains max range for the sensor
uint3 reading_type
uint16 d0 # Meters distance_cm
uint16 d45
uint16 d90
uint16 d135
uint16 d180
uint16 d225
uint16 d270
uint16 d315
Loading…
Cancel
Save