Browse Source

merge zbr-4.0

master
z 5 years ago
parent
commit
b02d479f80
  1. 4
      ArduCopter/Parameters.cpp
  2. 47
      ArduCopter/UserCode.cpp
  3. 9
      Tools/ardupilotwaf/git_submodule.py

4
ArduCopter/Parameters.cpp

@ -1624,7 +1624,7 @@ const char* Copter::get_sysid_board_id(void) @@ -1624,7 +1624,7 @@ const char* Copter::get_sysid_board_id(void)
int32_t nameValue1 =(int32_t) g.sysid_board_name_1st;
int32_t nameValue2 = (int32_t)g.sysid_board_name_2nd;
char name[6] = {' ',' ',' ',' ',' ','.'};
char name[7] = {' ',' ',' ',' ',' '};
// memset(name,0,6);
nameValue2 = nameValue2 & 0xffffff;
// name[5] = "a";
@ -1633,6 +1633,6 @@ const char* Copter::get_sysid_board_id(void) @@ -1633,6 +1633,6 @@ const char* Copter::get_sysid_board_id(void)
name[2] = nameValue2>>16& 0xFF;
name[1] = nameValue1&0xFF;
name[0] = nameValue1>>8 & 0xFF;
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.1,Board ID: ZRZK.%s.%d",name,(int)g.sysid_board_id);
return buf;
}

47
ArduCopter/UserCode.cpp

@ -57,28 +57,39 @@ void Copter::userhook_SlowLoop() @@ -57,28 +57,39 @@ void Copter::userhook_SlowLoop()
#endif
#ifdef USERHOOK_SUPERSLOWLOOP
static float batt_mah_teb[] =
{
25.20,24.90,24.84,24.76,24.69,24.64,24.60,24.57,24.54,24.52,
24.50,24.48,24.45,24.43,24.40,24.36,24.32,24.26,24.21,24.14,
24.07,24.00,23.94,23.88,23.79,23.71,23.65,23.58,23.51,23.46,
23.41,23.36,23.30,23.24,23.19,23.13,23.07,23.01,22.95,22.91,
22.86,22.81,22.76,22.70,22.65,22.59,22.54,22.48,22.43,22.37,
22.31,22.26,22.21,22.16,22.11,22.06,22.01,21.96,21.92,21.88,
21.84,21.79,21.76,21.72,21.69,21.64,21.59,21.54,21.49,21.45,
21.40,21.34,21.29,21.24,21.18,21.13,21.07,21.02,20.96,20.90,
20.85,20.80,20.75,20.69,20.63,20.56,20.47,20.29,20.16,20.04,
19.88,19.73,19.53,19.34,19.19,19.00,18.80,18.51,18.00,17.40,
16.80
};
void Copter::userhook_SuperSlowLoop()
{
// put your 1Hz code here
// if(!motors->armed())
// {
// camera.set_trigger_distance(0); // @Brown , stop take photos
// }
// float proximity_alt_diff;
// AP_Proximity *proximity = AP::proximity();
// if (proximity && proximity->get_horizontal_distance(0,proximity_alt_diff)) {
// if(proximity_alt_diff < 40.0)
// {
// if(control_mode != Mode::Number::BRAKE)
// gcs().send_text(MAV_SEVERITY_INFO, "Dist: %f, stop",proximity_alt_diff);
// control_mode = Mode::Number::BRAKE;
// }
static bool before_fly = true;
if(motors->armed())
before_fly = false;
if(before_fly){
uint8_t cnt,cacl_volt_pst;
float delt_volt;
for(cnt = 0; cnt<102; cnt++ ){
delt_volt = batt_mah_teb[cnt] - battery.voltage();
// delt_volt = batt_mah_teb[cnt] - test_volt;
if(delt_volt <= 0)
break;
}
cacl_volt_pst = 100 - cnt;
battery.reset_remaining(1, cacl_volt_pst);
}
// }
}
#endif

9
Tools/ardupilotwaf/git_submodule.py

@ -134,10 +134,11 @@ def git_submodule_update(self, name): @@ -134,10 +134,11 @@ def git_submodule_update(self, name):
@before_method('process_source')
def process_module_dependencies(self):
return
# self.git_submodule = getattr(self, 'git_submodule', '')
# if not self.git_submodule:
# self.bld.fatal('git_submodule: empty or missing git_submodule argument')
# self.git_submodule_update(self.git_submodule)
self.git_submodule = getattr(self, 'git_submodule', '')
if not self.git_submodule:
self.bld.fatal('git_submodule: empty or missing git_submodule argument')
self.git_submodule_update(self.git_submodule)
@conf
def git_submodule(bld, git_submodule, **kw):

Loading…
Cancel
Save