Browse Source

Merge remote-tracking branch 'nzeg/zbr-v4.0.4' into landtest

master
yaozb 5 years ago
parent
commit
5afcd3bec7
  1. 2
      .gitignore
  2. 2
      ArduCopter/AP_Arming.cpp
  3. 25
      ArduCopter/Parameters.cpp
  4. 4
      ArduCopter/Parameters.h
  5. 66
      ArduCopter/UserCode.cpp
  6. 14
      ArduCopter/events.cpp
  7. 32
      ArduCopter/motors.cpp
  8. 4
      ArduCopter/version.h
  9. 4
      Tools/Frame_params/Parrot_Disco/rcS_mode_default
  10. 4
      Tools/scripts/build_autotest.sh
  11. 5
      libraries/AP_Arming/AP_Arming.cpp
  12. 4
      libraries/AP_Arming/AP_Arming.h
  13. 3
      libraries/AP_BattMonitor/AP_BattMonitor.cpp
  14. 11
      libraries/AP_BattMonitor/AP_BattMonitor_Serial_BattGo.cpp
  15. 4
      libraries/AP_Camera/AP_Camera.cpp
  16. 6
      libraries/AP_Camera/AP_Camera.h
  17. 2
      libraries/AP_GPS/GPS_Backend.cpp
  18. 6
      libraries/AP_HAL/board/chibios.h
  19. 4
      libraries/AP_HAL_ChibiOS/Storage.cpp
  20. 4
      libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.dat
  21. 4
      libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat
  22. 4
      libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef.dat
  23. 4
      libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat
  24. 4
      libraries/AP_HAL_ChibiOS/hwdef/F35Lightning/hwdef.dat
  25. 4
      libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef.dat
  26. 4
      libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat
  27. 4
      libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat
  28. 4
      libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat
  29. 4
      libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing/hwdef.dat
  30. 4
      libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat
  31. 4
      libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v51/hwdef.dat
  32. 4
      libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v52/hwdef.dat
  33. 4
      libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v54/hwdef.dat
  34. 4
      libraries/AP_HAL_ChibiOS/hwdef/VRCore-v10/hwdef.dat
  35. 4
      libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef.dat
  36. 4
      libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat
  37. 4
      libraries/AP_HAL_ChibiOS/hwdef/fmuv4/hwdef.dat
  38. 14
      libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat
  39. 4
      libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef.dat
  40. 4
      libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef.dat
  41. 4
      libraries/AP_HAL_ChibiOS/hwdef/mindpx-v2/hwdef.dat
  42. 4
      libraries/AP_HAL_ChibiOS/hwdef/mini-pix/hwdef.dat
  43. 4
      libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef.dat
  44. 4
      libraries/AP_HAL_ChibiOS/sdcard.cpp
  45. 8
      libraries/AP_HAL_Linux/HAL_Linux_Class.cpp
  46. 4
      libraries/AP_Logger/AP_Logger.cpp
  47. 3
      libraries/AP_Logger/AP_Logger.h
  48. 4
      libraries/AP_Notify/AP_Notify.cpp
  49. 2
      libraries/AP_Notify/AP_Notify.h
  50. 447
      libraries/AP_Notify/Display.cpp
  51. 21
      libraries/AP_Notify/Display.h
  52. 37
      libraries/AP_Notify/ToshibaLED_I2C.cpp
  53. 2
      libraries/AP_Notify/ToshibaLED_I2C.h
  54. 20
      libraries/AP_Notify/UAVCAN_RGB_LED.cpp
  55. 5
      libraries/AP_Notify/UAVCAN_RGB_LED.h
  56. 13
      libraries/AP_OpticalFlow/OpticalFlow.cpp
  57. 1
      libraries/AP_OpticalFlow/OpticalFlow.h
  58. 2
      libraries/AP_Scripting/lua_scripts.cpp
  59. 8
      libraries/AP_SerialManager/AP_SerialManager.cpp

2
.gitignore vendored

@ -123,3 +123,5 @@ segv_*out
/ArduPlane/scripts/ /ArduPlane/scripts/
/ArduSub/scripts/ /ArduSub/scripts/
persistent.dat persistent.dat
.history

2
ArduCopter/AP_Arming.cpp

@ -457,7 +457,7 @@ bool AP_Arming_Copter::mandatory_deadline_checks(bool display_failure)
{ {
const AP_GPS &gps = AP::gps(); const AP_GPS &gps = AP::gps();
if(gps.status()<2) if(gps.status()<2)
return false; return true;
if (!copter.deadline_ok()) if (!copter.deadline_ok())
{ {
int32_t deadline = 0; int32_t deadline = 0;

25
ArduCopter/Parameters.cpp

@ -55,6 +55,8 @@ const AP_Param::Info Copter::var_info[] = {
// @Description: For mark board name last // @Description: For mark board name last
// @User: @Binsir // @User: @Binsir
GSCALAR(sysid_board_name_2nd, "SYSID_BDNAME_P2", 1001), GSCALAR(sysid_board_name_2nd, "SYSID_BDNAME_P2", 1001),
// 0:rs100, 1:M66, 2:RF610 3:zrzk.20qt2
GSCALAR(sysid_type, "SYSID_TYPE", 0 ),
// @Param: SYSID_THISMAV // @Param: SYSID_THISMAV
// @DisplayName: MAVLink system ID of this vehicle // @DisplayName: MAVLink system ID of this vehicle
@ -1640,9 +1642,26 @@ const char* Copter::get_sysid_board_id(void)
int32_t nameValue1 =(int32_t) g.sysid_board_name_1st; int32_t nameValue1 =(int32_t) g.sysid_board_name_1st;
int32_t nameValue2 = (int32_t)g.sysid_board_name_2nd; int32_t nameValue2 = (int32_t)g.sysid_board_name_2nd;
int8_t type = g.sysid_type;
// snprintf(buf, sizeof(buf), "Version: zr-v4.0.1 ,Board ID: ZRZK.20QT2.%d",(int)nameValue2); switch (type)
snprintf(buf, sizeof(buf), "Version: zr-v4.0.2 ,ID: RS100%04d%05d",(int)nameValue1,(int)nameValue2); {
case 0:
snprintf(buf, sizeof(buf), "Version: zr-v4.0.4 ,ID: RS100%04d%05d",(int)nameValue1,(int)nameValue2);
break;
case 1:
snprintf(buf, sizeof(buf), "Version: zr-v4.0.4 ,ID: M660%04d%05d",(int)nameValue1,(int)nameValue2);
break;
case 2:
snprintf(buf, sizeof(buf), "Version: zr-v4.0.4 ,ID: RF610%04d%05d",(int)nameValue1,(int)nameValue2);
break;
case 3:
snprintf(buf, sizeof(buf), "Version: zr-v4.0.4 ,Board ID: ZRZK.20QT2.%d",(int)nameValue2);
break;
default:
break;
}
AP::logger().Write_Message(buf);
return buf; return buf;
} }

4
ArduCopter/Parameters.h

@ -204,7 +204,7 @@ public:
k_param_sysid_board_name_1st =106, //add by @Binsir k_param_sysid_board_name_1st =106, //add by @Binsir
k_param_sysid_board_name_2nd=107, //add by @Binsir k_param_sysid_board_name_2nd=107, //add by @Binsir
k_param_sysid_board_id=108, // modify by @Brown k_param_sysid_type=108, // modify by @Brown
// 110: Telemetry control // 110: Telemetry control
// //
@ -394,7 +394,7 @@ public:
AP_Int16 format_version; AP_Int16 format_version;
// AP_Int32 sysid_board_id; // modify by @Brown AP_Int8 sysid_type; // modify by @Brown
AP_Int16 sysid_board_name_1st;// modify by @Binsir AP_Int16 sysid_board_name_1st;// modify by @Binsir
AP_Int16 sysid_board_name_2nd;// modify by @Binsir AP_Int16 sysid_board_name_2nd;// modify by @Binsir

66
ArduCopter/UserCode.cpp

@ -8,23 +8,9 @@ void Copter::userhook_init()
{ {
// put your initialisation code here // put your initialisation code here
// this will be called once at start-up // this will be called once at start-up
if (x30t != nullptr)
{ relay.on(1);
x30t->init();
}
else
{
if (x30t == nullptr)
{
gcs().send_text(MAV_SEVERITY_INFO,"x30t is null");
x30t = new AP_Camera_Serial_X30T();
if (x30t == nullptr || !x30t->init())
{
delete x30t;
x30t = nullptr;
}
}
}
} }
#endif #endif
@ -46,38 +32,6 @@ void Copter::userhook_50Hz()
void Copter::userhook_MediumLoop() void Copter::userhook_MediumLoop()
{ {
// put your 10Hz code here // put your 10Hz code here
if (x30t != nullptr)
{
int32_t lat = AP::gps().location().lat;
int32_t lng = AP::gps().location().lat;
int32_t alt = AP::gps().location().alt;
uint8_t posdata[12];
posdata[0] = lat & 0xff;
posdata[1] = (lat >> 8) & 0xff;
posdata[2] = (lat >> 16) & 0xff;
posdata[3] = (lat >> 24) & 0xff;
posdata[4] = lng & 0xff;
posdata[5] = (lng >> 8) & 0xff;
posdata[6] = (lng >> 16) & 0xff;
posdata[7] = (lng >> 24) & 0xff;
posdata[8] = alt& 0xff;
posdata[9] = (alt>> 8) & 0xff;
posdata[10] =(alt >> 16) & 0xff;
posdata[11] =(alt >> 24) & 0xff;
x30t->sendPos(&posdata[0],X30T_MSG_TYPE_POS);
}
} }
#endif #endif
@ -140,9 +94,8 @@ void Copter::userhook_SuperSlowLoop()
break; break;
} }
cacl_volt_pst = 100 - cnt; cacl_volt_pst = 100 - cnt;
battery.reset_remaining(1, cacl_volt_pst); battery.reset_remaining(0, cacl_volt_pst);
} }
} }
#endif #endif
@ -150,6 +103,17 @@ void Copter::userhook_SuperSlowLoop()
void Copter::userhook_auxSwitch1(uint8_t ch_flag) void Copter::userhook_auxSwitch1(uint8_t ch_flag)
{ {
// put your aux switch #1 handler here (CHx_OPT = 47) // put your aux switch #1 handler here (CHx_OPT = 47)
// switch (ch_flag) {
// case 2: {
// relay.on(2);
// break;
// }
// case 0: {
// relay.off(2);
// break;
// }
// }
} }
void Copter::userhook_auxSwitch2(uint8_t ch_flag) void Copter::userhook_auxSwitch2(uint8_t ch_flag)

14
ArduCopter/events.cpp

@ -102,6 +102,20 @@ void Copter::handle_battery_failsafe(const char *type_str, const int8_t action)
} else { } else {
gcs().send_text(MAV_SEVERITY_WARNING, "Battery Failsafe"); gcs().send_text(MAV_SEVERITY_WARNING, "Battery Failsafe");
} }
const AP_AHRS &_ahrs = AP::ahrs();
float home = 0.0;
Location loc;
if (_ahrs.get_position(loc)) {
const Location &home_loc = _ahrs.get_home();
if (home_loc.lat != 0 || home_loc.lng != 0) {
// distance between vehicle and home_loc in meters
home = home_loc.get_distance(loc);
if(home < 10) // @Brown, if distance to home less than 10m,don't action
{
desired_action = Failsafe_Action_None;
}
}
}
// Battery FS options already use the Failsafe_Options enum. So use them directly. // Battery FS options already use the Failsafe_Options enum. So use them directly.
do_failsafe_action(desired_action, ModeReason::BATTERY_FAILSAFE); do_failsafe_action(desired_action, ModeReason::BATTERY_FAILSAFE);

32
ArduCopter/motors.cpp

@ -26,24 +26,36 @@ void Copter::arm_motors_check()
} }
#endif #endif
int16_t yaw_in = channel_yaw->get_control_in();
int16_t pitch_in = channel_pitch->get_control_in();
int16_t roll_in = channel_roll->get_control_in();
int16_t throttle_in = channel_throttle->get_control_in();
static const uint16_t trim_trg_value = arming.get_rudder_arm_value()*40;
static const int8_t con_arm_delay = arming.get_rudder_arm_time();
// static uint8_t cnt;
// cnt++;
// if(cnt%20 == 0)
// gcs().send_text(MAV_SEVERITY_INFO,"v:%4d,t:%4d,y:%4d,p:%4d,r:%4d",trim_trg_value,throttle_in,yaw_in,pitch_in,roll_in);
// ensure throttle is down // ensure throttle is down
if (channel_throttle->get_control_in() > 0) { if (throttle_in > 1000-arming.get_rudder_arm_value()*10) {
arming_counter = 0; arming_counter = 0;
return; return;
} }
int16_t yaw_in = channel_yaw->get_control_in();
// full right // full right
if (yaw_in > 4000) { // if (yaw_in > 4000) {
if(yaw_in>trim_trg_value&&pitch_in>trim_trg_value&&roll_in< -trim_trg_value){
// if(yaw_in>trim_trg_value){
// increase the arming counter to a maximum of 1 beyond the auto trim counter // increase the arming counter to a maximum of 1 beyond the auto trim counter
if (arming_counter <= AUTO_TRIM_DELAY) { if (arming_counter <= AUTO_TRIM_DELAY) {
arming_counter++; arming_counter++;
} }
// arm the motors and configure for flight // arm the motors and configure for flight
if (arming_counter == ARM_DELAY && !motors->armed()) { // if (arming_counter == ARM_DELAY && !motors->armed()) {
if (arming_counter == con_arm_delay && !motors->armed()) {
// reset arming counter if arming fail // reset arming counter if arming fail
if (!arming.arm(AP_Arming::Method::RUDDER)) { if (!arming.arm(AP_Arming::Method::RUDDER)) {
arming_counter = 0; arming_counter = 0;
@ -58,19 +70,23 @@ void Copter::arm_motors_check()
} }
// full left and rudder disarming is enabled // full left and rudder disarming is enabled
} else if ((yaw_in < -4000) && (arming_rudder == AP_Arming::RudderArming::ARMDISARM)) { // } else if ((yaw_in < -4000) && (arming_rudder == AP_Arming::RudderArming::ARMDISARM)) {
} else if((yaw_in<-trim_trg_value&&pitch_in>trim_trg_value&&roll_in>trim_trg_value)&&(arming_rudder==AP_Arming::RudderArming::ARMDISARM)){
// } else if((yaw_in<-trim_trg_value)&&(arming_rudder==AP_Arming::RudderArming::ARMDISARM)){
if (!flightmode->has_manual_throttle() && !ap.land_complete) { if (!flightmode->has_manual_throttle() && !ap.land_complete) {
arming_counter = 0; arming_counter = 0;
return; return;
} }
// increase the counter to a maximum of 1 beyond the disarm delay // increase the counter to a maximum of 1 beyond the disarm delay
if (arming_counter <= DISARM_DELAY) { // if (arming_counter <= DISARM_DELAY) {
if (arming_counter <= con_arm_delay) {
arming_counter++; arming_counter++;
} }
// disarm the motors // disarm the motors
if (arming_counter == DISARM_DELAY && motors->armed()) { // if (arming_counter == DISARM_DELAY && motors->armed()) {
if (arming_counter == con_arm_delay && motors->armed()) {
arming.disarm(); arming.disarm();
} }

4
ArduCopter/version.h

@ -6,10 +6,10 @@
#include "ap_version.h" #include "ap_version.h"
#define THISFIRMWARE "ArduCopter V4.0.0" #define THISFIRMWARE "ZRUAV" //"ArduCopter V4.0.0"
// the following line is parsed by the autotest scripts // the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,0,0,FIRMWARE_VERSION_TYPE_OFFICIAL #define FIRMWARE_VERSION 4,0,3,FIRMWARE_VERSION_TYPE_OFFICIAL
#define FW_MAJOR 4 #define FW_MAJOR 4
#define FW_MINOR 0 #define FW_MINOR 0

4
Tools/Frame_params/Parrot_Disco/rcS_mode_default

@ -3,9 +3,9 @@
# default rcS running mode script # default rcS running mode script
echo $((1024*1024)) > /proc/sys/net/core/wmem_max # inscrease the max socket size echo $((1024*1024)) > /proc/sys/net/core/wmem_max # inscrease the max socket size
if test -x /data/ftp/internal_000/APM/start_ardupilot.sh; then if test -x /data/ftp/internal_000/ZRUAV/start_ardupilot.sh; then
ulogger -t "rcS_mode_default" -p I "Launching ArduPilot" ulogger -t "rcS_mode_default" -p I "Launching ArduPilot"
/data/ftp/internal_000/APM/start_ardupilot.sh /data/ftp/internal_000/ZRUAV/start_ardupilot.sh
else else
ulogger -t "rcS_mode_default" -p I "Launching Dragon" ulogger -t "rcS_mode_default" -p I "Launching Dragon"
DragonStarter.sh -out2null & DragonStarter.sh -out2null &

4
Tools/scripts/build_autotest.sh

@ -1,9 +1,9 @@
#!/bin/bash #!/bin/bash
export PATH=$HOME/.local/bin:/usr/local/bin:$HOME/prefix/bin:$HOME/APM/px4/gcc-arm-none-eabi-4_9-2015q3/bin:$PATH export PATH=$HOME/.local/bin:/usr/local/bin:$HOME/prefix/bin:$HOME/ZRUAV/px4/gcc-arm-none-eabi-4_9-2015q3/bin:$PATH
export PYTHONUNBUFFERED=1 export PYTHONUNBUFFERED=1
cd $HOME/APM || exit 1 cd $HOME/ZRUAV || exit 1
test -n "$FORCEBUILD" || { test -n "$FORCEBUILD" || {
(cd APM && git fetch > /dev/null 2>&1) (cd APM && git fetch > /dev/null 2>&1)

5
libraries/AP_Arming/AP_Arming.cpp

@ -115,6 +115,11 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = {
// @User: Standard // @User: Standard
AP_GROUPINFO("CHECK", 8, AP_Arming, checks_to_perform, ARMING_CHECK_ALL), AP_GROUPINFO("CHECK", 8, AP_Arming, checks_to_perform, ARMING_CHECK_ALL),
// @Brown ,摇杆解锁延时, *0.1s
AP_GROUPINFO("DELAY", 9, AP_Arming, rudder_arm_delay_dsec, 5),
// @Brown ,摇杆解锁量,百分比
AP_GROUPINFO("VPERC", 10, AP_Arming, rudder_arm_value_perc, 90),
AP_GROUPEND AP_GROUPEND
}; };

4
libraries/AP_Arming/AP_Arming.h

@ -79,6 +79,8 @@ public:
}; };
RudderArming get_rudder_arming_type() const { return (RudderArming)_rudder_arming.get(); } RudderArming get_rudder_arming_type() const { return (RudderArming)_rudder_arming.get(); }
int8_t get_rudder_arm_time() const { return rudder_arm_delay_dsec.get(); }
int8_t get_rudder_arm_value() const { return rudder_arm_value_perc.get(); }
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];
@ -89,6 +91,8 @@ protected:
AP_Int32 checks_to_perform; // bitmask for which checks are required AP_Int32 checks_to_perform; // bitmask for which checks are required
AP_Float accel_error_threshold; AP_Float accel_error_threshold;
AP_Int8 _rudder_arming; AP_Int8 _rudder_arming;
AP_Int8 rudder_arm_delay_dsec;
AP_Int8 rudder_arm_value_perc;
AP_Int32 _required_mission_items; AP_Int32 _required_mission_items;
// internal members // internal members

3
libraries/AP_BattMonitor/AP_BattMonitor.cpp

@ -147,7 +147,8 @@ AP_BattMonitor::init()
drivers[instance] = new AP_BattMonitor_FuelLevel_PWM(*this, state[instance], _params[instance]); drivers[instance] = new AP_BattMonitor_FuelLevel_PWM(*this, state[instance], _params[instance]);
break; break;
case AP_BattMonitor_Params::BattMonitor_Serial_BattGo: case AP_BattMonitor_Params::BattMonitor_Serial_BattGo:
drivers[instance] = new AP_BattMonitor_Serial_BattGo(*this, state[instance], _params[instance],instance);//TODO // drivers[instance] = new AP_BattMonitor_Serial_BattGo(*this, state[instance], _params[instance],instance);//TODO
drivers[instance] = new AP_BattMonitor_Serial_BattGo(*this, state[instance], _params[instance],0);//TODO
break; break;
case AP_BattMonitor_Params::BattMonitor_TYPE_NONE: case AP_BattMonitor_Params::BattMonitor_TYPE_NONE:
default: default:

11
libraries/AP_BattMonitor/AP_BattMonitor_Serial_BattGo.cpp

@ -70,6 +70,10 @@ bool AP_BattMonitor_Serial_BattGo::get_reading() //TODO need to Refactor
void AP_BattMonitor_Serial_BattGo::requestBattData(uint8_t data) void AP_BattMonitor_Serial_BattGo::requestBattData(uint8_t data)
{ {
if (uart == nullptr)
{
return ;
}
//发送data主要 0x40 0x42 0x44 地址0x21 及计算crc 均不会出现0x55,故不做0x55处理 //发送data主要 0x40 0x42 0x44 地址0x21 及计算crc 均不会出现0x55,故不做0x55处理
uint8_t send_data[13]; uint8_t send_data[13];
send_data[0] = 0x55; send_data[0] = 0x55;
@ -231,6 +235,7 @@ void AP_BattMonitor_Serial_BattGo::read()
{ {
requestBattData(BATTGO_CMD_REQUEST_ACTUAL_DATA); requestBattData(BATTGO_CMD_REQUEST_ACTUAL_DATA);
uint32_t tnow = AP_HAL::micros(); uint32_t tnow = AP_HAL::micros();
static uint32_t last_prt;
if (get_reading()) if (get_reading())
{ {
if (parseBattGo()) if (parseBattGo())
@ -257,15 +262,17 @@ void AP_BattMonitor_Serial_BattGo::read()
//... //...
_state.healthy = _interim_state.healthy; _state.healthy = _interim_state.healthy;
}else{ }else{
if(tnow-last_rev_batt_time>5000000){ if(tnow-last_rev_batt_time>5000000 && tnow - last_prt > 20000000 ){
_interim_state.healthy = false; _interim_state.healthy = false;
gcs().send_text(MAV_SEVERITY_INFO,"BATT_ERR:已经%d秒没有接收到智能电池 的串口数据!",(tnow-last_rev_batt_time)/1000000); gcs().send_text(MAV_SEVERITY_INFO,"BATT_ERR:已经%d秒没有接收到智能电池 的串口数据!",(tnow-last_rev_batt_time)/1000000);
last_prt = tnow;
} }
} }
}else{ }else{
if(tnow-last_rev_batt_time>5000000){ if(tnow-last_rev_batt_time>5000000 && tnow - last_prt > 20000000 ){
_interim_state.healthy = false; _interim_state.healthy = false;
gcs().send_text(MAV_SEVERITY_INFO,"BATT_ERR:已经%d秒没有接收到智能电池 的串口数据!",(tnow-last_rev_batt_time)/1000000); gcs().send_text(MAV_SEVERITY_INFO,"BATT_ERR:已经%d秒没有接收到智能电池 的串口数据!",(tnow-last_rev_batt_time)/1000000);
last_prt = tnow;
} }
} }
} }

4
libraries/AP_Camera/AP_Camera.cpp

@ -156,6 +156,8 @@ void AP_Camera::trigger_pic()
} }
log_picture(); log_picture();
AP_Notify::flags.image_index_log = number_of_log();
AP_Notify::flags.image_index = number_of_index();
} }
/// de-activate the trigger after some delay, but without using a delay() function /// de-activate the trigger after some delay, but without using a delay() function
@ -410,12 +412,14 @@ void AP_Camera::log_picture()
logger->Write_Camera(current_loc); logger->Write_Camera(current_loc);
last_pos_lat = current_loc.lat; last_pos_lat = current_loc.lat;
last_pos_lng = current_loc.lng; last_pos_lng = current_loc.lng;
_image_index_log++;
} }
} else { } else {
if (logger->should_log(log_camera_bit)) { if (logger->should_log(log_camera_bit)) {
logger->Write_Trigger(current_loc); logger->Write_Trigger(current_loc);
last_pos_lat = current_loc.lat; last_pos_lat = current_loc.lat;
last_pos_lng = current_loc.lng; last_pos_lng = current_loc.lng;
_image_index_log++;
} }
} }
} }

6
libraries/AP_Camera/AP_Camera.h

@ -78,6 +78,12 @@ public:
void get_last_trigger_pos(int32_t &lat,int32_t &lng){ lat=last_pos_lat;lng=last_pos_lng; } // @Brown,for get camera pos void get_last_trigger_pos(int32_t &lat,int32_t &lng){ lat=last_pos_lat;lng=last_pos_lng; } // @Brown,for get camera pos
// modivy by @Brown
uint16_t number_of_log(void) const { return _image_index_log; }
uint16_t number_of_index(void) const { return _image_index; }
uint16_t _image_index_log; // number of pictures taken to log @Brown
private: private:
static AP_Camera *_singleton; static AP_Camera *_singleton;

2
libraries/AP_GPS/GPS_Backend.cpp

@ -110,7 +110,7 @@ void AP_GPS_Backend::make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds)
//convert to time since Unix epoch //convert to time since Unix epoch
uint32_t ret =mkgmtime(timeinfo); uint32_t ret =mkgmtime(timeinfo);
//GPS epoch //GPS epoch
ret -= 315964800; //315964800 1980-1-6 - 1970 1- 1 ret -= 315964800 + 18; //315964800 1980-1-6 - 1970 1- 1,+18s tiaomiao
// // 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;

6
libraries/AP_HAL/board/chibios.h

@ -93,7 +93,7 @@
// allow for short names overridden in hwdef.dat // allow for short names overridden in hwdef.dat
#ifndef CHIBIOS_SHORT_BOARD_NAME #ifndef CHIBIOS_SHORT_BOARD_NAME
#define CHIBIOS_SHORT_BOARD_NAME CHIBIOS_BOARD_NAME #define CHIBIOS_SHORT_BOARD_NAME "ZrHardWare"
#endif #endif
#ifndef CONFIG_HAL_BOARD_SUBTYPE #ifndef CONFIG_HAL_BOARD_SUBTYPE
@ -109,7 +109,7 @@
#define HAL_I2C_INTERNAL_MASK 1 #define HAL_I2C_INTERNAL_MASK 1
#endif #endif
// put all storage of files under /APM directory // put all storage of files under /ZRUAV directory
#ifndef HAL_BOARD_STORAGE_DIRECTORY #ifndef HAL_BOARD_STORAGE_DIRECTORY
#define HAL_BOARD_STORAGE_DIRECTORY "/APM" #define HAL_BOARD_STORAGE_DIRECTORY "/ZRUAV"
#endif #endif

4
libraries/AP_HAL_ChibiOS/Storage.cpp

@ -31,12 +31,12 @@ extern const AP_HAL::HAL& hal;
#ifndef HAL_STORAGE_FILE #ifndef HAL_STORAGE_FILE
// using SKETCHNAME allows the one microSD to be used // using SKETCHNAME allows the one microSD to be used
// for multiple vehicle types // for multiple vehicle types
#define HAL_STORAGE_FILE "/APM/" SKETCHNAME ".stg" #define HAL_STORAGE_FILE "/ZRUAV/" SKETCHNAME ".stg"
#endif #endif
#ifndef HAL_STORAGE_BACKUP_FILE #ifndef HAL_STORAGE_BACKUP_FILE
// location of backup file // location of backup file
#define HAL_STORAGE_BACKUP_FILE "/APM/" SKETCHNAME ".bak" #define HAL_STORAGE_BACKUP_FILE "/ZRUAV/" SKETCHNAME ".bak"
#endif #endif
#define STORAGE_FLASH_RETRIES 5 #define STORAGE_FLASH_RETRIES 5

4
libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.dat

@ -270,8 +270,8 @@ define HAL_CHIBIOS_ARCH_FMUV3 1
define BOARD_TYPE_DEFAULT 3 define BOARD_TYPE_DEFAULT 3
# Nnow some defines for logging and terrain data files. # Nnow some defines for logging and terrain data files.
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
# allow to have have a dedicated safety switch pin # allow to have have a dedicated safety switch pin
define HAL_HAVE_SAFETY_SWITCH 1 define HAL_HAVE_SAFETY_SWITCH 1

4
libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat

@ -435,8 +435,8 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_CHIBIOS_ARCH_FMUV3 1 define HAL_CHIBIOS_ARCH_FMUV3 1
# now some defines for logging and terrain data files # now some defines for logging and terrain data files
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
# we need to tell HAL_ChibiOS/Storage.cpp how much storage is # we need to tell HAL_ChibiOS/Storage.cpp how much storage is
# available (in bytes) # available (in bytes)

4
libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef.dat

@ -227,8 +227,8 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_CHIBIOS_ARCH_FMUV4PRO 1 define HAL_CHIBIOS_ARCH_FMUV4PRO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
define HAL_STORAGE_SIZE 16384 define HAL_STORAGE_SIZE 16384
define HAL_WITH_RAMTRON 1 define HAL_WITH_RAMTRON 1

4
libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat

@ -323,8 +323,8 @@ define HAL_COMPASS_AUTO_ROT_DEFAULT 2
# enable FAT filesystem support (needs a microSD defined via SDMMC) # enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1 define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin

4
libraries/AP_HAL_ChibiOS/hwdef/F35Lightning/hwdef.dat

@ -147,8 +147,8 @@ define HAL_PROBE_EXTERNAL_I2C_BAROS
# no onboard SD, filesystem support disabled until flash logging implemented # no onboard SD, filesystem support disabled until flash logging implemented
#define HAL_OS_FATFS_IO 1 #define HAL_OS_FATFS_IO 1
#define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" #define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
#define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" #define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
# OSD support # OSD support
define OSD_ENABLED ENABLED define OSD_ENABLED ENABLED

4
libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef.dat

@ -108,8 +108,8 @@ define HAL_WITH_RAMTRON 1
# enable FAT filesystem support # enable FAT filesystem support
define HAL_OS_FATFS_IO 1 define HAL_OS_FATFS_IO 1
# now some defines for logging and terrain data files # now some defines for logging and terrain data files
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
# this defines the default maximum clock on I2C devices. # this defines the default maximum clock on I2C devices.
define HAL_I2C_MAX_CLOCK 100000 define HAL_I2C_MAX_CLOCK 100000

4
libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat

@ -144,8 +144,8 @@ IMU Invensense SPI:mpu6000 ROTATION_YAW_180
BARO BMP280 I2C:0:0x76 BARO BMP280 I2C:0:0x76
define HAL_OS_FATFS_IO 1 define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
# setup for OSD # setup for OSD
define OSD_ENABLED ENABLED define OSD_ENABLED ENABLED

4
libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat

@ -152,8 +152,8 @@ IMU Invensense SPI:mpu6000 ROTATION_YAW_180
BARO BMP280 I2C:0:0x76 BARO BMP280 I2C:0:0x76
define HAL_OS_FATFS_IO 1 define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
# define default battery setup # define default battery setup
define HAL_BATT_MONITOR_DEFAULT 4 define HAL_BATT_MONITOR_DEFAULT 4

4
libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat

@ -156,8 +156,8 @@ SPIDEV osd SPI2 DEVID1 MAX7456_CS MODE0 10*MHZ 10*MHZ
# filesystem setup on sdcard # filesystem setup on sdcard
define HAL_OS_FATFS_IO 1 define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
# 8 PWM available by default # 8 PWM available by default
define BOARD_PWM_COUNT_DEFAULT 8 define BOARD_PWM_COUNT_DEFAULT 8

4
libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing/hwdef.dat

@ -197,8 +197,8 @@ BARO BMP388 I2C:0:0x76
BARO MS56XX I2C:0:0x77 BARO MS56XX I2C:0:0x77
define HAL_OS_FATFS_IO 1 define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
# setup for OSD # setup for OSD
define OSD_ENABLED ENABLED define OSD_ENABLED ENABLED

4
libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat

@ -124,8 +124,8 @@ SPIDEV sdcard SPI4 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
SPIDEV osd SPI2 DEVID1 MAX7456_CS MODE0 10*MHZ 10*MHZ SPIDEV osd SPI2 DEVID1 MAX7456_CS MODE0 10*MHZ 10*MHZ
define HAL_OS_FATFS_IO 1 define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
# no built-in compass, but probe the i2c bus for all possible # no built-in compass, but probe the i2c bus for all possible
# external compass types # external compass types

4
libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v51/hwdef.dat

@ -132,8 +132,8 @@ SPIDEV sdcard SPI3 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
define HAL_CHIBIOS_ARCH_BRAINV51 1 define HAL_CHIBIOS_ARCH_BRAINV51 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
define HAL_STORAGE_SIZE 16384 define HAL_STORAGE_SIZE 16384
define STORAGE_FLASH_PAGE 22 define STORAGE_FLASH_PAGE 22

4
libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v52/hwdef.dat

@ -132,8 +132,8 @@ SPIDEV sdcard SPI3 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
define HAL_CHIBIOS_ARCH_BRAINV52 1 define HAL_CHIBIOS_ARCH_BRAINV52 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
define HAL_STORAGE_SIZE 16384 define HAL_STORAGE_SIZE 16384
define STORAGE_FLASH_PAGE 22 define STORAGE_FLASH_PAGE 22

4
libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v54/hwdef.dat

@ -132,8 +132,8 @@ SPIDEV sdcard SPI3 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
define HAL_CHIBIOS_ARCH_BRAINV54 1 define HAL_CHIBIOS_ARCH_BRAINV54 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
define HAL_STORAGE_SIZE 16384 define HAL_STORAGE_SIZE 16384
define STORAGE_FLASH_PAGE 22 define STORAGE_FLASH_PAGE 22

4
libraries/AP_HAL_ChibiOS/hwdef/VRCore-v10/hwdef.dat

@ -132,8 +132,8 @@ SPIDEV sdcard SPI3 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
define HAL_CHIBIOS_ARCH_COREV10 1 define HAL_CHIBIOS_ARCH_COREV10 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
define HAL_STORAGE_SIZE 16384 define HAL_STORAGE_SIZE 16384
define STORAGE_FLASH_PAGE 22 define STORAGE_FLASH_PAGE 22

4
libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef.dat

@ -132,8 +132,8 @@ SPIDEV sdcard SPI3 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
define HAL_CHIBIOS_ARCH_UBRAINV51 1 define HAL_CHIBIOS_ARCH_UBRAINV51 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
define HAL_STORAGE_SIZE 15360 define HAL_STORAGE_SIZE 15360
define STORAGE_FLASH_PAGE 2 define STORAGE_FLASH_PAGE 2

4
libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat

@ -438,8 +438,8 @@ SPIDEV pixartPC15 SPI4 DEVID13 ACCEL_EXT_CS MODE3 2*MHZ 2*MHZ
define HAL_CHIBIOS_ARCH_FMUV3 1 define HAL_CHIBIOS_ARCH_FMUV3 1
# Nnow some defines for logging and terrain data files. # Nnow some defines for logging and terrain data files.
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
# We need to tell HAL_ChibiOS/Storage.cpp how much storage is # We need to tell HAL_ChibiOS/Storage.cpp how much storage is
# available (in bytes). # available (in bytes).

4
libraries/AP_HAL_ChibiOS/hwdef/fmuv4/hwdef.dat

@ -174,8 +174,8 @@ SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
define HAL_CHIBIOS_ARCH_FMUV4 1 define HAL_CHIBIOS_ARCH_FMUV4 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
define HAL_STORAGE_SIZE 16384 define HAL_STORAGE_SIZE 16384

14
libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat

@ -159,7 +159,7 @@ PD12 USART3_RTS USART3
PD0 UART4_RX UART4 NODMA PD0 UART4_RX UART4 NODMA
PD1 UART4_TX UART4 NODMA PD1 UART4_TX UART4 NODMA
# USART6 is telem3 # # USART6 is telem3
PG9 USART6_RX USART6 NODMA PG9 USART6_RX USART6 NODMA
# we leave PG14 as an input to prevent it acting as a pullup # we leave PG14 as an input to prevent it acting as a pullup
# on the IOMCU SBUS input # on the IOMCU SBUS input
@ -167,6 +167,14 @@ PG9 USART6_RX USART6 NODMA
PG15 USART6_CTS USART6 PG15 USART6_CTS USART6
PG8 USART6_RTS USART6 PG8 USART6_RTS USART6
# # USART6 is telem3 for cube
# PG9 USART6_RX USART6 NODMA
# # we leave PG14 as an input to prevent it acting as a pullup
# # on the IOMCU SBUS input
# PG14 USART6_TX USART6 NODMA
# # PG15 USART6_CTS USART6
# # PG8 USART6_RTS USART6
# UART7 is debug # UART7 is debug
PF6 UART7_RX UART7 NODMA PF6 UART7_RX UART7 NODMA
PE8 UART7_TX UART7 NODMA PE8 UART7_TX UART7 NODMA
@ -321,8 +329,8 @@ DMA_PRIORITY SDMMC* UART8* ADC* SPI* TIM*
# enable FAT filesystem support (needs a microSD defined via SDMMC) # enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1 define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin

4
libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef.dat

@ -236,8 +236,8 @@ SPIDEV bmi088_g SPI5 DEVID1 BMI088_GYRO_CS MODE3 10*MHZ 10*MHZ
SPIDEV bmi088_a SPI5 DEVID2 BMI088_ACCEL_CS MODE3 10*MHZ 10*MHZ SPIDEV bmi088_a SPI5 DEVID2 BMI088_ACCEL_CS MODE3 10*MHZ 10*MHZ
# Now some defines for logging and terrain data files. # Now some defines for logging and terrain data files.
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
# allow to have have a dedicated safety switch pin # allow to have have a dedicated safety switch pin
define HAL_HAVE_SAFETY_SWITCH 1 define HAL_HAVE_SAFETY_SWITCH 1

4
libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef.dat

@ -399,8 +399,8 @@ SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
define HAL_CHIBIOS_ARCH_FMUV3 1 define HAL_CHIBIOS_ARCH_FMUV3 1
# now some defines for logging and terrain data files # now some defines for logging and terrain data files
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
# we need to tell HAL_ChibiOS/Storage.cpp how much storage is # we need to tell HAL_ChibiOS/Storage.cpp how much storage is
# available (in bytes) # available (in bytes)

4
libraries/AP_HAL_ChibiOS/hwdef/mindpx-v2/hwdef.dat

@ -186,8 +186,8 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_CHIBIOS_ARCH_MINDPXV2 1 define HAL_CHIBIOS_ARCH_MINDPXV2 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
define HAL_STORAGE_SIZE 16384 define HAL_STORAGE_SIZE 16384

4
libraries/AP_HAL_ChibiOS/hwdef/mini-pix/hwdef.dat

@ -128,8 +128,8 @@ COMPASS QMC5883L I2C:0:0x0D false ROTATION_PITCH_180_YAW_270
define HAL_PROBE_EXTERNAL_I2C_COMPASSES define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 1 define HAL_I2C_INTERNAL_MASK 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
define HAL_STORAGE_SIZE 16384 define HAL_STORAGE_SIZE 16384

4
libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef.dat

@ -116,8 +116,8 @@ define STORAGE_FLASH_PAGE 1
define HAL_STORAGE_SIZE 15360 define HAL_STORAGE_SIZE 15360
define HAL_OS_FATFS_IO 1 define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_LOG_DIRECTORY "/ZRUAV/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_BOARD_TERRAIN_DIRECTORY "/ZRUAV/TERRAIN"
# define default battery setup # define default battery setup
define HAL_BATT_VOLT_PIN 12 define HAL_BATT_VOLT_PIN 12

4
libraries/AP_HAL_ChibiOS/sdcard.cpp

@ -79,7 +79,7 @@ bool sdcard_init()
printf("Successfully mounted SDCard (slowdown=%u)\n", (unsigned)sd_slowdown); printf("Successfully mounted SDCard (slowdown=%u)\n", (unsigned)sd_slowdown);
// Create APM Directory if needed // Create APM Directory if needed
AP::FS().mkdir("/APM"); AP::FS().mkdir("/ZRUAV");
sdcard_running = true; sdcard_running = true;
return true; return true;
} }
@ -124,7 +124,7 @@ bool sdcard_init()
printf("Successfully mounted SDCard (slowdown=%u)\n", (unsigned)sd_slowdown); printf("Successfully mounted SDCard (slowdown=%u)\n", (unsigned)sd_slowdown);
// Create APM Directory if needed // Create APM Directory if needed
AP::FS().mkdir("/APM"); AP::FS().mkdir("/ZRUAV");
return true; return true;
} }
#endif #endif

8
libraries/AP_HAL_Linux/HAL_Linux_Class.cpp

@ -252,11 +252,11 @@ void _usage(void)
printf("\t -A udp:11.0.0.255:14550:bcast\n"); printf("\t -A udp:11.0.0.255:14550:bcast\n");
printf("\t -A udpin:0.0.0.0:14550\n"); printf("\t -A udpin:0.0.0.0:14550\n");
printf("\tcustom log path:\n"); printf("\tcustom log path:\n");
printf("\t --log-directory /var/APM/logs\n"); printf("\t --log-directory /var/ZRUAV/logs\n");
printf("\t -l /var/APM/logs\n"); printf("\t -l /var/ZRUAV/logs\n");
printf("\tcustom terrain path:\n"); printf("\tcustom terrain path:\n");
printf("\t --terrain-directory /var/APM/terrain\n"); printf("\t --terrain-directory /var/ZRUAV/terrain\n");
printf("\t -t /var/APM/terrain\n"); printf("\t -t /var/ZRUAV/terrain\n");
#if AP_MODULE_SUPPORTED #if AP_MODULE_SUPPORTED
printf("\tmodule support:\n"); printf("\tmodule support:\n");
printf("\t --module-directory %s\n", AP_MODULE_DEFAULT_DIRECTORY); printf("\t --module-directory %s\n", AP_MODULE_DEFAULT_DIRECTORY);

4
libraries/AP_Logger/AP_Logger.cpp

@ -93,6 +93,9 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = {
// @Units: s // @Units: s
AP_GROUPINFO("_FILE_TIMEOUT", 6, AP_Logger, _params.file_timeout, HAL_LOGGING_FILE_TIMEOUT), AP_GROUPINFO("_FILE_TIMEOUT", 6, AP_Logger, _params.file_timeout, HAL_LOGGING_FILE_TIMEOUT),
AP_GROUPINFO("_LAST_LOG", 7, AP_Logger, _params.last_log_num, 0),
AP_GROUPEND AP_GROUPEND
}; };
@ -211,6 +214,7 @@ void AP_Logger::Init(const struct LogStructure *structures, uint8_t num_types)
EnableWrites(true); EnableWrites(true);
gcs().send_text(MAV_SEVERITY_INFO, "Prepared log system"); gcs().send_text(MAV_SEVERITY_INFO, "Prepared log system");
set_last_log_num();
} }
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #if CONFIG_HAL_BOARD == HAL_BOARD_SITL

3
libraries/AP_Logger/AP_Logger.h

@ -338,8 +338,11 @@ public:
AP_Int8 log_replay; AP_Int8 log_replay;
AP_Int8 mav_bufsize; // in kilobytes AP_Int8 mav_bufsize; // in kilobytes
AP_Int16 file_timeout; // in seconds AP_Int16 file_timeout; // in seconds
AP_Int16 last_log_num; // in seconds
} _params; } _params;
void set_last_log_num() { _params.last_log_num = find_last_log() ; }
const struct LogStructure *structure(uint16_t num) const; const struct LogStructure *structure(uint16_t num) const;
const struct UnitStructure *unit(uint16_t num) const; const struct UnitStructure *unit(uint16_t num) const;
const struct MultiplierStructure *multiplier(uint16_t num) const; const struct MultiplierStructure *multiplier(uint16_t num) const;

4
libraries/AP_Notify/AP_Notify.cpp

@ -241,10 +241,10 @@ void AP_Notify::add_backends(void)
#endif #endif
break; break;
case Notify_LED_ToshibaLED_I2C_Internal: case Notify_LED_ToshibaLED_I2C_Internal:
ADD_BACKEND(new ToshibaLED_I2C(TOSHIBA_LED_I2C_BUS_INTERNAL)); ADD_BACKEND(new ToshibaLED_I2C(2));
break; break;
case Notify_LED_ToshibaLED_I2C_External: case Notify_LED_ToshibaLED_I2C_External:
ADD_BACKEND(new ToshibaLED_I2C(TOSHIBA_LED_I2C_BUS_EXTERNAL)); ADD_BACKEND(new ToshibaLED_I2C(3));
break; break;
#if !HAL_MINIMIZE_FEATURES #if !HAL_MINIMIZE_FEATURES
case Notify_LED_NCP5623_I2C_External: case Notify_LED_NCP5623_I2C_External:

2
libraries/AP_Notify/AP_Notify.h

@ -100,6 +100,8 @@ public:
bool waiting_for_throw; // true when copter is in THROW mode and waiting to detect the user hand launch bool waiting_for_throw; // true when copter is in THROW mode and waiting to detect the user hand launch
bool powering_off; // true when the vehicle is powering off bool powering_off; // true when the vehicle is powering off
bool video_recording; // true when the vehicle is recording video bool video_recording; // true when the vehicle is recording video
uint16_t image_index ; // camera images ,add by @Brown
uint16_t image_index_log ; // camera images to log
}; };
/// notify_events_type - bitmask of active events. /// notify_events_type - bitmask of active events.

447
libraries/AP_Notify/Display.cpp

@ -322,6 +322,197 @@ static_assert(ARRAY_SIZE(_font) == 1280, "_font is correct size");
static_assert(ARRAY_SIZE(_font) == 475, "_font is correct size"); static_assert(ARRAY_SIZE(_font) == 475, "_font is correct size");
#endif #endif
static const unsigned char _font_16[]=
{
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,// 0
0x00,0x00,0x00,0xF8,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x33,0x30,0x00,0x00,0x00,//! 1
0x00,0x10,0x0C,0x06,0x10,0x0C,0x06,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,//" 2
0x40,0xC0,0x78,0x40,0xC0,0x78,0x40,0x00,0x04,0x3F,0x04,0x04,0x3F,0x04,0x04,0x00,//# 3
0x00,0x70,0x88,0xFC,0x08,0x30,0x00,0x00,0x00,0x18,0x20,0xFF,0x21,0x1E,0x00,0x00,//$ 4
0xF0,0x08,0xF0,0x00,0xE0,0x18,0x00,0x00,0x00,0x21,0x1C,0x03,0x1E,0x21,0x1E,0x00,//% 5
0x00,0xF0,0x08,0x88,0x70,0x00,0x00,0x00,0x1E,0x21,0x23,0x24,0x19,0x27,0x21,0x10,//& 6
0x10,0x16,0x0E,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,//' 7
0x00,0x00,0x00,0xE0,0x18,0x04,0x02,0x00,0x00,0x00,0x00,0x07,0x18,0x20,0x40,0x00,//( 8
0x00,0x02,0x04,0x18,0xE0,0x00,0x00,0x00,0x00,0x40,0x20,0x18,0x07,0x00,0x00,0x00,//) 9
0x40,0x40,0x80,0xF0,0x80,0x40,0x40,0x00,0x02,0x02,0x01,0x0F,0x01,0x02,0x02,0x00,//* 10
0x00,0x00,0x00,0xF0,0x00,0x00,0x00,0x00,0x01,0x01,0x01,0x1F,0x01,0x01,0x01,0x00,//+ 11
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x80,0xB0,0x70,0x00,0x00,0x00,0x00,0x00,//, 12
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0x01,0x01,0x01,0x01,0x01,0x01,//- 13
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x30,0x30,0x00,0x00,0x00,0x00,0x00,//. 14
0x00,0x00,0x00,0x00,0x80,0x60,0x18,0x04,0x00,0x60,0x18,0x06,0x01,0x00,0x00,0x00,/// 15
0x00,0xE0,0x10,0x08,0x08,0x10,0xE0,0x00,0x00,0x0F,0x10,0x20,0x20,0x10,0x0F,0x00,//0 16
0x00,0x10,0x10,0xF8,0x00,0x00,0x00,0x00,0x00,0x20,0x20,0x3F,0x20,0x20,0x00,0x00,//1 17
0x00,0x70,0x08,0x08,0x08,0x88,0x70,0x00,0x00,0x30,0x28,0x24,0x22,0x21,0x30,0x00,//2 18
0x00,0x30,0x08,0x88,0x88,0x48,0x30,0x00,0x00,0x18,0x20,0x20,0x20,0x11,0x0E,0x00,//3 19
0x00,0x00,0xC0,0x20,0x10,0xF8,0x00,0x00,0x00,0x07,0x04,0x24,0x24,0x3F,0x24,0x00,//4 20
0x00,0xF8,0x08,0x88,0x88,0x08,0x08,0x00,0x00,0x19,0x21,0x20,0x20,0x11,0x0E,0x00,//5 21
0x00,0xE0,0x10,0x88,0x88,0x18,0x00,0x00,0x00,0x0F,0x11,0x20,0x20,0x11,0x0E,0x00,//6 22
0x00,0x38,0x08,0x08,0xC8,0x38,0x08,0x00,0x00,0x00,0x00,0x3F,0x00,0x00,0x00,0x00,//7 23
0x00,0x70,0x88,0x08,0x08,0x88,0x70,0x00,0x00,0x1C,0x22,0x21,0x21,0x22,0x1C,0x00,//8 24
0x00,0xE0,0x10,0x08,0x08,0x10,0xE0,0x00,0x00,0x00,0x31,0x22,0x22,0x11,0x0F,0x00,//9 25
0x00,0x00,0x00,0xC0,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x30,0x30,0x00,0x00,0x00,//: 26
0x00,0x00,0x00,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x80,0x60,0x00,0x00,0x00,0x00,//; 27
0x00,0x00,0x80,0x40,0x20,0x10,0x08,0x00,0x00,0x01,0x02,0x04,0x08,0x10,0x20,0x00,//< 28
0x40,0x40,0x40,0x40,0x40,0x40,0x40,0x00,0x04,0x04,0x04,0x04,0x04,0x04,0x04,0x00,//= 29
0x00,0x08,0x10,0x20,0x40,0x80,0x00,0x00,0x00,0x20,0x10,0x08,0x04,0x02,0x01,0x00,//> 30
0x00,0x70,0x48,0x08,0x08,0x08,0xF0,0x00,0x00,0x00,0x00,0x30,0x36,0x01,0x00,0x00,//? 31
0xC0,0x30,0xC8,0x28,0xE8,0x10,0xE0,0x00,0x07,0x18,0x27,0x24,0x23,0x14,0x0B,0x00,//@ 32
0x00,0x00,0xC0,0x38,0xE0,0x00,0x00,0x00,0x20,0x3C,0x23,0x02,0x02,0x27,0x38,0x20,//A 33
0x08,0xF8,0x88,0x88,0x88,0x70,0x00,0x00,0x20,0x3F,0x20,0x20,0x20,0x11,0x0E,0x00,//B 34
0xC0,0x30,0x08,0x08,0x08,0x08,0x38,0x00,0x07,0x18,0x20,0x20,0x20,0x10,0x08,0x00,//C 35
0x08,0xF8,0x08,0x08,0x08,0x10,0xE0,0x00,0x20,0x3F,0x20,0x20,0x20,0x10,0x0F,0x00,//D 36
0x08,0xF8,0x88,0x88,0xE8,0x08,0x10,0x00,0x20,0x3F,0x20,0x20,0x23,0x20,0x18,0x00,//E 37
0x08,0xF8,0x88,0x88,0xE8,0x08,0x10,0x00,0x20,0x3F,0x20,0x00,0x03,0x00,0x00,0x00,//F 38
0xC0,0x30,0x08,0x08,0x08,0x38,0x00,0x00,0x07,0x18,0x20,0x20,0x22,0x1E,0x02,0x00,//G 39
0x08,0xF8,0x08,0x00,0x00,0x08,0xF8,0x08,0x20,0x3F,0x21,0x01,0x01,0x21,0x3F,0x20,//H 40
0x00,0x08,0x08,0xF8,0x08,0x08,0x00,0x00,0x00,0x20,0x20,0x3F,0x20,0x20,0x00,0x00,//I 41
0x00,0x00,0x08,0x08,0xF8,0x08,0x08,0x00,0xC0,0x80,0x80,0x80,0x7F,0x00,0x00,0x00,//J 42
0x08,0xF8,0x88,0xC0,0x28,0x18,0x08,0x00,0x20,0x3F,0x20,0x01,0x26,0x38,0x20,0x00,//K 43
0x08,0xF8,0x08,0x00,0x00,0x00,0x00,0x00,0x20,0x3F,0x20,0x20,0x20,0x20,0x30,0x00,//L 44
0x08,0xF8,0xF8,0x00,0xF8,0xF8,0x08,0x00,0x20,0x3F,0x00,0x3F,0x00,0x3F,0x20,0x00,//M 45
0x08,0xF8,0x30,0xC0,0x00,0x08,0xF8,0x08,0x20,0x3F,0x20,0x00,0x07,0x18,0x3F,0x00,//N 46
0xE0,0x10,0x08,0x08,0x08,0x10,0xE0,0x00,0x0F,0x10,0x20,0x20,0x20,0x10,0x0F,0x00,//O 47
0x08,0xF8,0x08,0x08,0x08,0x08,0xF0,0x00,0x20,0x3F,0x21,0x01,0x01,0x01,0x00,0x00,//P 48
0xE0,0x10,0x08,0x08,0x08,0x10,0xE0,0x00,0x0F,0x18,0x24,0x24,0x38,0x50,0x4F,0x00,//Q 49
0x08,0xF8,0x88,0x88,0x88,0x88,0x70,0x00,0x20,0x3F,0x20,0x00,0x03,0x0C,0x30,0x20,//R 50
0x00,0x70,0x88,0x08,0x08,0x08,0x38,0x00,0x00,0x38,0x20,0x21,0x21,0x22,0x1C,0x00,//S 51
0x18,0x08,0x08,0xF8,0x08,0x08,0x18,0x00,0x00,0x00,0x20,0x3F,0x20,0x00,0x00,0x00,//T 52
0x08,0xF8,0x08,0x00,0x00,0x08,0xF8,0x08,0x00,0x1F,0x20,0x20,0x20,0x20,0x1F,0x00,//U 53
0x08,0x78,0x88,0x00,0x00,0xC8,0x38,0x08,0x00,0x00,0x07,0x38,0x0E,0x01,0x00,0x00,//V 54
0xF8,0x08,0x00,0xF8,0x00,0x08,0xF8,0x00,0x03,0x3C,0x07,0x00,0x07,0x3C,0x03,0x00,//W 55
0x08,0x18,0x68,0x80,0x80,0x68,0x18,0x08,0x20,0x30,0x2C,0x03,0x03,0x2C,0x30,0x20,//X 56
0x08,0x38,0xC8,0x00,0xC8,0x38,0x08,0x00,0x00,0x00,0x20,0x3F,0x20,0x00,0x00,0x00,//Y 57
0x10,0x08,0x08,0x08,0xC8,0x38,0x08,0x00,0x20,0x38,0x26,0x21,0x20,0x20,0x18,0x00,//Z 58
0x00,0x00,0x00,0xFE,0x02,0x02,0x02,0x00,0x00,0x00,0x00,0x7F,0x40,0x40,0x40,0x00,//[ 59
0x00,0x0C,0x30,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0x06,0x38,0xC0,0x00,//\ 60
0x00,0x02,0x02,0x02,0xFE,0x00,0x00,0x00,0x00,0x40,0x40,0x40,0x7F,0x00,0x00,0x00,//] 61
0x00,0x00,0x04,0x02,0x02,0x02,0x04,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,//^ 62
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,//_ 63
0x00,0x02,0x02,0x04,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,//` 64
0x00,0x00,0x80,0x80,0x80,0x80,0x00,0x00,0x00,0x19,0x24,0x22,0x22,0x22,0x3F,0x20,//a 65
0x08,0xF8,0x00,0x80,0x80,0x00,0x00,0x00,0x00,0x3F,0x11,0x20,0x20,0x11,0x0E,0x00,//b 66
0x00,0x00,0x00,0x80,0x80,0x80,0x00,0x00,0x00,0x0E,0x11,0x20,0x20,0x20,0x11,0x00,//c 67
0x00,0x00,0x00,0x80,0x80,0x88,0xF8,0x00,0x00,0x0E,0x11,0x20,0x20,0x10,0x3F,0x20,//d 68
0x00,0x00,0x80,0x80,0x80,0x80,0x00,0x00,0x00,0x1F,0x22,0x22,0x22,0x22,0x13,0x00,//e 69
0x00,0x80,0x80,0xF0,0x88,0x88,0x88,0x18,0x00,0x20,0x20,0x3F,0x20,0x20,0x00,0x00,//f 70
0x00,0x00,0x80,0x80,0x80,0x80,0x80,0x00,0x00,0x6B,0x94,0x94,0x94,0x93,0x60,0x00,//g 71
0x08,0xF8,0x00,0x80,0x80,0x80,0x00,0x00,0x20,0x3F,0x21,0x00,0x00,0x20,0x3F,0x20,//h 72
0x00,0x80,0x98,0x98,0x00,0x00,0x00,0x00,0x00,0x20,0x20,0x3F,0x20,0x20,0x00,0x00,//i 73
0x00,0x00,0x00,0x80,0x98,0x98,0x00,0x00,0x00,0xC0,0x80,0x80,0x80,0x7F,0x00,0x00,//j 74
0x08,0xF8,0x00,0x00,0x80,0x80,0x80,0x00,0x20,0x3F,0x24,0x02,0x2D,0x30,0x20,0x00,//k 75
0x00,0x08,0x08,0xF8,0x00,0x00,0x00,0x00,0x00,0x20,0x20,0x3F,0x20,0x20,0x00,0x00,//l 76
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x00,0x20,0x3F,0x20,0x00,0x3F,0x20,0x00,0x3F,//m 77
0x80,0x80,0x00,0x80,0x80,0x80,0x00,0x00,0x20,0x3F,0x21,0x00,0x00,0x20,0x3F,0x20,//n 78
0x00,0x00,0x80,0x80,0x80,0x80,0x00,0x00,0x00,0x1F,0x20,0x20,0x20,0x20,0x1F,0x00,//o 79
0x80,0x80,0x00,0x80,0x80,0x00,0x00,0x00,0x80,0xFF,0xA1,0x20,0x20,0x11,0x0E,0x00,//p 80
0x00,0x00,0x00,0x80,0x80,0x80,0x80,0x00,0x00,0x0E,0x11,0x20,0x20,0xA0,0xFF,0x80,//q 81
0x80,0x80,0x80,0x00,0x80,0x80,0x80,0x00,0x20,0x20,0x3F,0x21,0x20,0x00,0x01,0x00,//r 82
0x00,0x00,0x80,0x80,0x80,0x80,0x80,0x00,0x00,0x33,0x24,0x24,0x24,0x24,0x19,0x00,//s 83
0x00,0x80,0x80,0xE0,0x80,0x80,0x00,0x00,0x00,0x00,0x00,0x1F,0x20,0x20,0x00,0x00,//t 84
0x80,0x80,0x00,0x00,0x00,0x80,0x80,0x00,0x00,0x1F,0x20,0x20,0x20,0x10,0x3F,0x20,//u 85
0x80,0x80,0x80,0x00,0x00,0x80,0x80,0x80,0x00,0x01,0x0E,0x30,0x08,0x06,0x01,0x00,//v 86
0x80,0x80,0x00,0x80,0x00,0x80,0x80,0x80,0x0F,0x30,0x0C,0x03,0x0C,0x30,0x0F,0x00,//w 87
0x00,0x80,0x80,0x00,0x80,0x80,0x80,0x00,0x00,0x20,0x31,0x2E,0x0E,0x31,0x20,0x00,//x 88
0x80,0x80,0x80,0x00,0x00,0x80,0x80,0x80,0x80,0x81,0x8E,0x70,0x18,0x06,0x01,0x00,//y 89
0x00,0x80,0x80,0x80,0x80,0x80,0x80,0x00,0x00,0x21,0x30,0x2C,0x22,0x21,0x30,0x00,//z 90
0x00,0x00,0x00,0x00,0x80,0x7C,0x02,0x02,0x00,0x00,0x00,0x00,0x00,0x3F,0x40,0x40,//{ 91
0x00,0x00,0x00,0x00,0xFF,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xFF,0x00,0x00,0x00,//| 92
0x00,0x02,0x02,0x7C,0x80,0x00,0x00,0x00,0x00,0x40,0x40,0x3F,0x00,0x00,0x00,0x00,//} 93
0x00,0x06,0x01,0x01,0x02,0x02,0x04,0x04,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,//~ 94
};
/// 致(0) 睿(1) 智(2) 控(3) 云(4) 台(5)
static unsigned char ZRZKYT[][32]={
{0x00,0x00,0xFF,0x05,0x05,0xF5,0x55,0x5D,0x55,0x55,0x55,0x55,0xF5,0x05,0x01,0x00},
{0x40,0x30,0x0F,0x80,0xA0,0x97,0xBD,0x55,0x55,0x55,0x55,0x55,0xB7,0x80,0x80,0x00},/*"厦",0*/
{0x00,0xF8,0x01,0x06,0x00,0x00,0x02,0x02,0x02,0x02,0x02,0x02,0x02,0xFE,0x00,0x00},
{0x00,0xFF,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x40,0x80,0x7F,0x00,0x00},/*"门",1*/
{0x42,0x62,0x5A,0xC6,0x52,0x62,0xC2,0x20,0xD8,0x17,0x10,0x10,0xF0,0x10,0x10,0x00},
{0x40,0xC4,0x44,0x7F,0x24,0x24,0xA0,0x40,0x21,0x16,0x08,0x16,0x21,0x40,0x80,0x00},/*"致",2*/
{0x20,0x18,0x88,0xA8,0x68,0x28,0xA8,0x6F,0xAA,0x2A,0x6A,0xAA,0x0A,0x28,0x18,0x00},
{0x04,0x04,0x02,0xFE,0xAB,0xAB,0xAA,0xAA,0xAA,0xAB,0xAB,0xFE,0x02,0x04,0x04,0x00},/*"睿",3*/
{0x10,0x94,0x53,0x32,0x1E,0x32,0x52,0x10,0x00,0x7E,0x42,0x42,0x42,0x7E,0x00,0x00},
{0x00,0x00,0x00,0xFF,0x49,0x49,0x49,0x49,0x49,0x49,0x49,0xFF,0x00,0x00,0x00,0x00},/*"智",4*/
{0x10,0x10,0x10,0xFF,0x90,0x20,0x98,0x48,0x28,0x09,0x0E,0x28,0x48,0xA8,0x18,0x00},
{0x02,0x42,0x81,0x7F,0x00,0x40,0x40,0x42,0x42,0x42,0x7E,0x42,0x42,0x42,0x40,0x00},/*"控",5*/
};
unsigned char gImage_zr12864[] = {
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x08,0x38,0xF8,0xF8,0xF8,0xF8,0xF8,0xF8,0xF8,0xF8,0xF8,0xF8,0xF8,
0xF8,0xF8,0xF8,0xF8,0x78,0x18,0x00,0xC0,0xF0,0xF0,0xF0,0xE0,0xC0,0x80,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x10,0xB0,0xF0,0x70,0x30,0x30,0x30,0xB0,0x30,
0x00,0xC0,0xF0,0x30,0x30,0x30,0x30,0xF0,0xF0,0x30,0x00,0x00,0x00,0x00,0xC0,0xC0,
0x40,0x78,0x78,0x50,0x50,0x50,0x50,0x50,0x50,0x50,0x50,0x50,0x50,0xD0,0xD0,0xC0,
0x00,0x00,0x00,0x00,0x00,0xF0,0xB0,0x90,0xF0,0xF0,0xB0,0x90,0x90,0x80,0x00,0xF0,
0xF0,0x30,0x30,0x30,0xF0,0xF0,0x00,0x00,0x00,0x00,0xC0,0xC0,0xF8,0xF0,0xC0,0x00,
0x00,0xF0,0xF0,0x30,0x30,0x30,0x38,0x38,0x30,0x30,0xF0,0xF0,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x01,0x01,0x03,0x83,0xE3,0xFB,0xFF,0xFF,0xFF,0x7F,
0x3F,0x0F,0x83,0xE0,0xF8,0xFE,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFC,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x67,0x67,0x66,0xFE,0xFE,0x66,0x67,0x67,
0x00,0x01,0x03,0x98,0xF8,0xF0,0xFC,0x0F,0x03,0x00,0x00,0x00,0x00,0x00,0x01,0xF5,
0xF4,0xB5,0xBD,0xBF,0xBF,0xA9,0xA9,0xA9,0xAF,0xBF,0xBF,0xBD,0xBC,0xF4,0xF5,0x01,
0x00,0x00,0x00,0x00,0x00,0xEC,0xE4,0x36,0x37,0x33,0x37,0x34,0x3C,0x30,0x30,0x37,
0x37,0x36,0x36,0xF6,0xE7,0xE7,0x00,0x00,0x00,0x00,0x60,0x60,0xFF,0xFF,0x30,0x10,
0x00,0x05,0x67,0x66,0x63,0x63,0xE0,0xE0,0x63,0x66,0x66,0x65,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x80,0xC0,0xF0,0xFC,0xFF,0xFF,0xFF,0x7F,0x1F,0x87,0x01,0x10,
0x7C,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0x7F,0x3F,0x1F,0x0F,0x03,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x8C,0x8C,0x8F,0x0F,0x0C,0x8C,0x04,
0x00,0x00,0x8E,0x07,0x01,0x80,0x03,0x07,0x0E,0x00,0x00,0x00,0x80,0x80,0x80,0x0F,
0x0F,0x0A,0x8A,0x0A,0x0A,0x0A,0x8A,0x0A,0x0A,0x8A,0x0A,0x0A,0x0A,0x0F,0x0F,0x00,
0x80,0x80,0x80,0x80,0x00,0x0F,0x8F,0x09,0x09,0x09,0x89,0x09,0x09,0x89,0x09,0x09,
0x09,0x09,0x09,0x0F,0x8F,0x0F,0x00,0x00,0x80,0x00,0x08,0x88,0x8F,0x8F,0x00,0x00,
0x00,0x88,0x88,0x08,0x08,0x88,0x0F,0x0F,0x08,0x08,0x88,0x88,0x80,0x00,0x00,0x00,
0x00,0x00,0x00,0x3E,0x3F,0x3F,0x3F,0x1F,0x0F,0x03,0x20,0x38,0x3E,0x3F,0x3F,0x3E,
0x38,0x01,0x03,0x0F,0x3F,0x3F,0x3F,0x3F,0x3F,0x3F,0x3F,0x3E,0x38,0x20,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x30,0x38,0x24,0x23,0x21,0x00,0x00,0x3F,0x04,
0x04,0x04,0x3F,0x00,0x00,0x3F,0x00,0x00,0x00,0x00,0x00,0x00,0x3F,0x04,0x04,0x3B,
0x00,0x00,0x1F,0x20,0x20,0x20,0x1F,0x00,0x00,0x3F,0x00,0x00,0x00,0x00,0x00,0x00,
0x30,0x28,0x26,0x23,0x00,0x00,0x3F,0x04,0x04,0x04,0x3F,0x00,0x00,0x3F,0x00,0x00,
0x00,0x00,0x00,0x00,0x3F,0x06,0x0A,0x11,0x20,0x00,0x1F,0x20,0x20,0x20,0x1F,0x00,
0x00,0x3F,0x03,0x06,0x18,0x3F,0x00,0x00,0x0E,0x11,0x20,0x20,0x24,0x1C,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,/*"d:\Users\z\Pictures\应用\转尺寸\ZR12864w2.bmp",0*/
};
bool Display::init(void) bool Display::init(void)
{ {
// exit immediately if already initialised // exit immediately if already initialised
@ -399,6 +590,9 @@ void Display::update()
void Display::update_all() void Display::update_all()
{ {
update_display_manual();
return;
update_text(0); update_text(0);
update_mode(1); update_mode(1);
update_battery(2); update_battery(2);
@ -433,15 +627,55 @@ void Display::draw_char(uint16_t x, uint16_t y, const char c)
{ {
uint8_t line; uint8_t line;
static uint8_t Size = 16;
uint8_t i,j;
// draw char to pixel // draw char to pixel
for (uint8_t i = 0; i < 6; i++) { if(Size == 16)
{
for ( i = 0; i < 9; i++) {
if (i == 8) {
line = 0;
} else {
line = _font_16[(c * 16) + i];
}
for ( j = 0; j < 8; j++) {
if (line & 1) {
_driver->set_pixel(x + i, y + j );
} else {
_driver->clear_pixel(x + i, y + j );
}
line >>= 1;
}
}
for ( i = 0; i < 9; i++) {
if (i == 8) {
line = 0;
} else {
line = _font_16[(c * 16) + 8 + i];
}
for ( j = 0; j < 8; j++) {
if (line & 1) {
_driver->set_pixel(x + i, y + 8 + j);
} else {
_driver->clear_pixel(x + i, y + 8 + j);
}
line >>= 1;
}
}
}else{
for ( i = 0; i < 6; i++) {
if (i == 5) { if (i == 5) {
line = 0; line = 0;
} else { } else {
line = _font[(c * 5) + i]; line = _font[(c * 5) + i];
} }
for (uint8_t j = 0; j < 8; j++) { for ( j = 0; j < 8; j++) {
if (line & 1) { if (line & 1) {
_driver->set_pixel(x + i, y + j); _driver->set_pixel(x + i, y + j);
} else { } else {
@ -451,6 +685,7 @@ void Display::draw_char(uint16_t x, uint16_t y, const char c)
} }
} }
} }
}
void Display::update_arm(uint8_t r) void Display::update_arm(uint8_t r)
{ {
@ -523,9 +758,14 @@ void Display::update_ekf(uint8_t r)
void Display::update_battery(uint8_t r) void Display::update_battery(uint8_t r)
{ {
// char msg [DISPLAY_MESSAGE_SIZE];
// snprintf(msg, DISPLAY_MESSAGE_SIZE, "BAT1: %4.2fV", (double)AP::battery().voltage()) ;
// draw_text(COLUMN(0), ROW(r), msg);
char msg [DISPLAY_MESSAGE_SIZE]; char msg [DISPLAY_MESSAGE_SIZE];
snprintf(msg, DISPLAY_MESSAGE_SIZE, "BAT1: %4.2fV", (double)AP::battery().voltage()) ; snprintf(msg, DISPLAY_MESSAGE_SIZE, "BAT1: %2.1fV,GPS:%2u", (double)AP::battery().voltage(), (unsigned)AP_Notify::flags.gps_num_sats) ;
draw_text(COLUMN(0), ROW(r), msg); draw_text(COLUMN(0), ROW(r), msg);
} }
void Display::update_mode(uint8_t r) void Display::update_mode(uint8_t r)
@ -580,3 +820,204 @@ void Display::update_text(uint8_t r)
draw_text(COLUMN(0), ROW(0), msg); draw_text(COLUMN(0), ROW(0), msg);
} }
void Display::draw_chinese(uint8_t x,uint8_t y,unsigned char hz[][32],uint8_t no)
{
uint8_t i,j,line = 0;
for ( i = 0; i < 17; i++) {
if (i == 16) {
line = 0;
} else {
line = hz[2 * no][i];
}
for ( j = 0; j < 8; j++) {
if (line & 1) {
_driver->set_pixel(x + i, y + j );
} else {
_driver->clear_pixel(x + i, y + j );
}
line >>= 1;
}
}
for ( i = 0; i < 17; i++) {
if (i == 16) {
line = 0;
} else {
line = hz[2 * no + 1][i];
}
for ( j = 0; j < 8; j++) {
if (line & 1) {
_driver->set_pixel(x + i, y + 8 + j);
} else {
_driver->clear_pixel(x + i, y + 8 + j);
}
line >>= 1;
}
}
}
void Display::draw_BMP(uint8_t x0,uint8_t y0,uint8_t x1,uint8_t y1,unsigned char BMP[])
{
uint16_t i = 0;
uint16_t j = 0;
uint8_t x,y;
uint8_t line = BMP[0];
// if(y1%8 == 0)
// y = y1/8;
// else
// y = y1/8 +1;
for(y=0; y<64; y+=8)
{
for(x=0; x<128; x++)
{
line = BMP[i++];
for ( j = 0; j < 8; j++) {
if (line & 1) {
_driver->set_pixel(x, y + j);
} else {
_driver->clear_pixel(x + i, y + j);
}
line >>= 1;
}
}
}
}
void Display::display_clear(void)
{
for(int i = 0; i < 64; i++)
{
for(int j = 0; j<128; j++){
_driver->clear_pixel(j , i);
}
}
}
void Display::update_chinese(uint8_t r)
{
draw_chinese(COLUMN(0), ROW(r),ZRZKYT,0);
draw_chinese(COLUMN(3), ROW(r),ZRZKYT,1);
draw_chinese(COLUMN(6), ROW(r),ZRZKYT,2);
draw_chinese(COLUMN(9), ROW(r),ZRZKYT,3);
draw_chinese(COLUMN(12), ROW(r),ZRZKYT,4);
draw_chinese(COLUMN(15), ROW(r),ZRZKYT,5);
}
void Display::update_camera(uint8_t r)
{
// char msg [DISPLAY_MESSAGE_SIZE];
// snprintf(msg, DISPLAY_MESSAGE_SIZE, "BAT1: %2.2fV,GPS:%2u", (double)AP::battery().voltage(), (unsigned)AP_Notify::flags.gps_num_sats) ;
// draw_text(COLUMN(0), ROW(r), msg);
char msg2 [DISPLAY_MESSAGE_SIZE];
snprintf(msg2, DISPLAY_MESSAGE_SIZE, "IMG: %4d,L: %4d ", AP_Notify::flags.image_index,AP_Notify::flags.image_index_log) ;
draw_text(COLUMN(0), ROW(r), msg2);
}
void Display::update_display_manual()
{
static uint8_t time_cnt;
static uint8_t display_stage = 1;
// if (time_cnt++ > 10) {
// time_cnt = 0;
// display_stage++;
// }
// if(display_stage>5)
// display_stage = 1;
RESTART1:
switch (display_stage)
{
case 1:
display_clear();
display_stage = 2;
case 2:
draw_BMP(0,0,128,8,gImage_zr12864); // 绘制图片
if (time_cnt++ > 10) {
time_cnt = 0;
display_stage++;
}
break;
case 3:
display_clear();
display_stage = 4;
case 4:
// update_text(0);
update_chinese(0);
update_camera(2);
update_battery(4);
break;
// case 5:
// // update_text(0);
// update_chinese(0);
// // update_gps(2);
// update_camera(4);
// break;
// case 6:
// display_stage = 1;
// goto RESTART1;
// // update_text(0);
// update_chinese(0);
// update_mode(2);
// update_battery(4);
// break;
// case 7:
// // update_text(0);
// update_chinese(0);
// update_gps(2);
// update_camera(4);
// break;
// case 8:
// display_stage = 1;
// goto RESTART1;
default:
break;
}
}
/*
check if feedback pin is high
*/
// void Display::trigger_pin_timer(void)
// {
// int8_t dpin = hal.gpio->analogPinToDigitalPin(_feedback_pin);
// if (dpin == -1) {
// return;
// }
// // ensure we are in input mode
// hal.gpio->pinMode(dpin, HAL_GPIO_INPUT);
// // enable pullup
// hal.gpio->write(dpin, 1);
// uint8_t pin_state = hal.gpio->read(dpin);
// uint8_t trigger_polarity = _feedback_polarity==0?0:1;
// if (pin_state == trigger_polarity &&
// _last_pin_state != trigger_polarity) {
// _page_turn = true;
// }
// _last_pin_state = pin_state;
// }

21
libraries/AP_Notify/Display.h

@ -16,6 +16,8 @@ public:
bool init(void) override; bool init(void) override;
void update() override; void update() override;
void update_display_manual();
private: private:
void draw_char(uint16_t x, uint16_t y, const char c); void draw_char(uint16_t x, uint16_t y, const char c);
void draw_text(uint16_t x, uint16_t y, const char *c); void draw_text(uint16_t x, uint16_t y, const char *c);
@ -30,6 +32,15 @@ private:
void update_text(uint8_t r); void update_text(uint8_t r);
void update_text_empty(uint8_t r); void update_text_empty(uint8_t r);
void draw_chinese(uint8_t x,uint8_t y,unsigned char hz[][32],uint8_t no);
void update_chinese(uint8_t r);
void update_camera(uint8_t r);
void display_clear(void);
void draw_BMP(uint8_t x0,uint8_t y0,uint8_t x1,uint8_t y1,unsigned char BMP[]);
Display_Backend *_driver; Display_Backend *_driver;
uint8_t _mstartpos; // ticker shift position uint8_t _mstartpos; // ticker shift position
@ -38,5 +49,15 @@ private:
// stop showing text in display after this many millis: // stop showing text in display after this many millis:
const uint16_t _send_text_valid_millis = 20000; const uint16_t _send_text_valid_millis = 20000;
/////////////////// @Brown ///////////////////
// void trigger_pin_timer(void);
// AP_Int8 _feedback_pin;
// AP_Int8 _feedback_polarity;
// uint8_t _last_pin_state;
// bool _page_turn;
// bool _timer_installed = false;
/////////////////////////////////////////////
}; };

37
libraries/AP_Notify/ToshibaLED_I2C.cpp

@ -48,11 +48,12 @@ ToshibaLED_I2C::ToshibaLED_I2C(uint8_t bus)
bool ToshibaLED_I2C::hw_init(void) bool ToshibaLED_I2C::hw_init(void)
{ {
// first look for led on external bus // first look for led on external bus
// _dev = std::move(hal.i2c_mgr->get_device(_bus, TOSHIBA_LED_I2C_ADDR)); _dev = std::move(hal.i2c_mgr->get_device(_bus, TOSHIBA_LED_I2C_ADDR));
FOREACH_I2C(i) { // FOREACH_I2C(i) {
_dev = std::move(hal.i2c_mgr->get_device(i, TOSHIBA_LED_I2C_ADDR)); // index_iic[i] = i;
} // _dev = std::move(hal.i2c_mgr->get_device(i, TOSHIBA_LED_I2C_ADDR));
// }
if (!_dev) { if (!_dev) {
return false; return false;
@ -76,16 +77,42 @@ bool ToshibaLED_I2C::hw_init(void)
if (ret) { if (ret) {
_dev->register_periodic_callback(20000, FUNCTOR_BIND_MEMBER(&ToshibaLED_I2C::_timer, void)); _dev->register_periodic_callback(20000, FUNCTOR_BIND_MEMBER(&ToshibaLED_I2C::_timer, void));
} }
// index_iic[4] = 99;
// _dev->transfer(index_iic, 5, nullptr, 0);
// test[0] = 99;
// test[1] = 99;
// test[2] = 99;
// test[3] = 99;
// test[4] = 99;
// _dev->transfer(test, 5, nullptr, 0);
return ret; return ret;
} }
// set_rgb - set color as a combination of red, green and blue values // set_rgb - set color as a combination of red, green and blue values
bool ToshibaLED_I2C::hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue) bool ToshibaLED_I2C::hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue)
{ {
// rgb = {red, green, blue};
// _need_update = true;
// return true;
static uint8_t cnt;
static uint8_t l_mode,l_red,l_green,l_blue;
rgb = {red, green, blue}; rgb = {red, green, blue};
cnt++;
if(l_mode != rgb_mode || l_red != rgb.r || l_green != rgb.g || l_blue != rgb.b || cnt > 50)
{
cnt =0;
_need_update = true; _need_update = true;
l_mode = rgb_mode ;
l_red = rgb.r ;
l_green = rgb.g ;
l_blue = rgb.b;
}
return true; return true;
} }
void ToshibaLED_I2C::set_rgb_mode(uint8_t mode) void ToshibaLED_I2C::set_rgb_mode(uint8_t mode)

2
libraries/AP_Notify/ToshibaLED_I2C.h

@ -37,4 +37,6 @@ private:
} rgb; } rgb;
uint8_t _bus; uint8_t _bus;
uint8_t rgb_mode; uint8_t rgb_mode;
uint8_t index_iic[5];
uint8_t test[5];
}; };

20
libraries/AP_Notify/UAVCAN_RGB_LED.cpp

@ -18,6 +18,7 @@
#include <AP_HAL/system.h> #include <AP_HAL/system.h>
#if HAL_WITH_UAVCAN #if HAL_WITH_UAVCAN
// #if 1
#include "UAVCAN_RGB_LED.h" #include "UAVCAN_RGB_LED.h"
#include <AP_UAVCAN/AP_UAVCAN.h> #include <AP_UAVCAN/AP_UAVCAN.h>
@ -54,10 +55,29 @@ bool UAVCAN_RGB_LED::hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue)
bool success = false; bool success = false;
uint8_t can_num_drivers = AP::can().get_num_drivers(); uint8_t can_num_drivers = AP::can().get_num_drivers();
static uint8_t cnt;
static uint8_t l_mode,l_red,l_green,l_blue;
rgb = {red, green, blue};
cnt++;
if(l_mode != rgb_mode || l_red != rgb.r || l_green != rgb.g || l_blue != rgb.b || cnt > 50)
{
cnt =0;
_need_update = true;
l_mode = rgb_mode ;
l_red = rgb.r ;
l_green = rgb.g ;
l_blue = rgb.b;
}else{
return success;
}
for (uint8_t i = 0; i < can_num_drivers; i++) { for (uint8_t i = 0; i < can_num_drivers; i++) {
AP_UAVCAN *uavcan = AP_UAVCAN::get_uavcan(i); AP_UAVCAN *uavcan = AP_UAVCAN::get_uavcan(i);
if (uavcan != nullptr) { if (uavcan != nullptr) {
// success = uavcan->led_write(_led_index, red, green, blue) || success; // success = uavcan->led_write(_led_index, red, green, blue) || success;
// success = uavcan->send_zr_rgb_led(rgb_mode,red, green, blue) || success;//(_led_index, red, green, blue) || success
success = uavcan->send_zr_rgb_led(rgb_mode,red, green, blue) || success;//(_led_index, red, green, blue) || success success = uavcan->send_zr_rgb_led(rgb_mode,red, green, blue) || success;//(_led_index, red, green, blue) || success
} }
} }

5
libraries/AP_Notify/UAVCAN_RGB_LED.h

@ -13,7 +13,12 @@ protected:
virtual bool hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue) override; virtual bool hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue) override;
void set_rgb_mode(uint8_t mode) override; void set_rgb_mode(uint8_t mode) override;
private: private:
void _timer(void);
uint8_t _led_index; uint8_t _led_index;
uint8_t rgb_mode; uint8_t rgb_mode;
bool _need_update;
struct {
uint8_t r, g, b;
} rgb;
}; };

13
libraries/AP_OpticalFlow/OpticalFlow.cpp

@ -83,6 +83,12 @@ const AP_Param::GroupInfo OpticalFlow::var_info[] = {
// @User: Advanced // @User: Advanced
AP_GROUPINFO("_ADDR", 5, OpticalFlow, _address, 0), AP_GROUPINFO("_ADDR", 5, OpticalFlow, _address, 0),
// @Param: _THRES
// @Description: min surface_quality value, below this value don't use flow
// @Range: 0 127
// @User: Brown
AP_GROUPINFO("_THRES", 6, OpticalFlow, _threshold, 100),
// the parameter description below is for GCSs (like MP) that use master for the parameter descriptions. This should be removed when Copter-3.7 is released // the parameter description below is for GCSs (like MP) that use master for the parameter descriptions. This should be removed when Copter-3.7 is released
// @Param: _ENABLE // @Param: _ENABLE
// @DisplayName: Optical flow enable/disable // @DisplayName: Optical flow enable/disable
@ -161,7 +167,8 @@ void OpticalFlow::update(void)
} }
// only healthy if the data is less than 0.5s old // only healthy if the data is less than 0.5s old
_flags.healthy = (AP_HAL::millis() - _last_update_ms < 500); // _flags.healthy = (AP_HAL::millis() - _last_update_ms < 500);
_flags.healthy = (AP_HAL::millis() - _last_update_ms < 500)&&(_state.surface_quality > _threshold);
} }
void OpticalFlow::handle_msg(const mavlink_message_t &msg) void OpticalFlow::handle_msg(const mavlink_message_t &msg)
@ -181,6 +188,10 @@ void OpticalFlow::update_state(const OpticalFlow_state &state)
_state = state; _state = state;
_last_update_ms = AP_HAL::millis(); _last_update_ms = AP_HAL::millis();
if(_state.surface_quality < _threshold )
{
_state.surface_quality = 0;
}
// write to log and send to EKF if new data has arrived // write to log and send to EKF if new data has arrived
AP::ahrs_navekf().writeOptFlowMeas(quality(), AP::ahrs_navekf().writeOptFlowMeas(quality(),
_state.flowRate, _state.flowRate,

1
libraries/AP_OpticalFlow/OpticalFlow.h

@ -111,6 +111,7 @@ private:
AP_Int16 _yawAngle_cd; // yaw angle of sensor X axis with respect to vehicle X axis - centi degrees AP_Int16 _yawAngle_cd; // yaw angle of sensor X axis with respect to vehicle X axis - centi degrees
AP_Vector3f _pos_offset; // position offset of the flow sensor in the body frame AP_Vector3f _pos_offset; // position offset of the flow sensor in the body frame
AP_Int8 _address; // address on the bus (allows selecting between 8 possible I2C addresses for px4flow) AP_Int8 _address; // address on the bus (allows selecting between 8 possible I2C addresses for px4flow)
AP_Int8 _threshold; // address on the bus (allows selecting between 8 possible I2C addresses for px4flow)
// method called by backend to update frontend state: // method called by backend to update frontend state:
void update_state(const OpticalFlow_state &state); void update_state(const OpticalFlow_state &state);

2
libraries/AP_Scripting/lua_scripts.cpp

@ -23,7 +23,7 @@
#ifndef SCRIPTING_DIRECTORY #ifndef SCRIPTING_DIRECTORY
#if HAL_OS_FATFS_IO #if HAL_OS_FATFS_IO
#define SCRIPTING_DIRECTORY "/APM/scripts" #define SCRIPTING_DIRECTORY "/ZRUAV/scripts"
#else #else
#define SCRIPTING_DIRECTORY "./scripts" #define SCRIPTING_DIRECTORY "./scripts"
#endif //HAL_OS_FATFS_IO #endif //HAL_OS_FATFS_IO

8
libraries/AP_SerialManager/AP_SerialManager.cpp

@ -456,6 +456,14 @@ void AP_SerialManager::init()
AP_SERIALMANAGER_SLCAN_BUFSIZE_TX); AP_SERIALMANAGER_SLCAN_BUFSIZE_TX);
break; break;
case SerialProtocol_Battery:
state[i].baud = AP_SERIALMANAGER_ALEXMOS_BAUD / 1000; // update baud param in case user looks at it
state[i].uart->begin(map_baudrate(state[i].baud),
AP_SERIALMANAGER_SLCAN_BUFSIZE_RX,
AP_SERIALMANAGER_SLCAN_BUFSIZE_TX);
break;
#ifndef HAL_BUILD_AP_PERIPH #ifndef HAL_BUILD_AP_PERIPH
case SerialProtocol_RCIN: case SerialProtocol_RCIN:
AP::RC().add_uart(state[i].uart); AP::RC().add_uart(state[i].uart);

Loading…
Cancel
Save