Browse Source

4轴测试5天没问题

mission-4.1.18
zbr 4 years ago
parent
commit
4b0d0badfa
  1. 80
      ArduCopter/UserCode.cpp
  2. 1
      ArduCopter/mode_auto.cpp
  3. 2
      ArduCopter/version.h
  4. 7
      ArduCopter/zr_flight.cpp
  5. 20
      libraries/AP_Camera/AP_Camera.cpp
  6. 3
      libraries/AP_Camera/AP_Camera.h
  7. 4
      libraries/AP_UAVCAN/AP_UAVCAN.cpp

80
ArduCopter/UserCode.cpp

@ -40,55 +40,6 @@ void Copter::userhook_50Hz() @@ -40,55 +40,6 @@ void Copter::userhook_50Hz()
void Copter::userhook_MediumLoop()
{
// put your 10Hz code here
#if CAM_DEBUG
static uint64_t prt_cnt;
uint16_t rc7_in = RC_Channels::rc_channel(CH_7)->get_radio_in();
switch (in_debug_mode)
{
case 0:
if(rc7_in > 1600){
in_debug_mode = 1;
}
break;
case 1:
if(rc7_in < 1600){
in_debug_mode = 2;
}
break;
case 2:
if(rc7_in > 1600){
in_debug_mode = 3;
}
break;
case 3:
if(rc7_in < 1600){
in_debug_mode = 4;
}
break;
case 4:
if(rc7_in > 1600){
in_debug_mode = 0;
}
break;
default:
break;
}
if(in_debug_mode == 4 || control_mode==Mode::Number::SPORT){
prt_cnt++;
if(!motors->armed()){
arming.arm(AP_Arming::Method::SCRIPTING);
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: debug mode arm!");
}
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: cnt:%lld",prt_cnt);
camera.take_picture();
}else{
prt_cnt = 0;
}
#endif
}
#endif
@ -107,20 +58,9 @@ void Copter::userhook_SuperSlowLoop() @@ -107,20 +58,9 @@ void Copter::userhook_SuperSlowLoop()
// put your 1Hz code here
zr_SuperSlowLoop();
#if CAM_DEBUG
// static uint64_t prt_cnt;
// if(in_debug_mode == 2 || control_mode==Mode::Number::ACRO){
// prt_cnt++;
// if(!motors->armed()){
// arming.arm(AP_Arming::Method::SCRIPTING);
// gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: debug mode arm!");
// }
// gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: cnt:%lld",prt_cnt);
// camera.take_picture();
// }else{
// prt_cnt = 0;
// }
if(in_debug_mode == 2 || control_mode==Mode::Number::ACRO){
camera.take_picture();
}
#endif
}
@ -146,15 +86,15 @@ void Copter::userhook_auxSwitch1(uint8_t ch_flag) @@ -146,15 +86,15 @@ void Copter::userhook_auxSwitch1(uint8_t ch_flag)
case 2: {
// relay.on(2);
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: debug mode 2!");
in_debug_mode = 4;
break;
}
case 1: {
// relay.on(2);
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: debug mode 1!");
in_debug_mode = 1;
in_debug_mode = 2;
break;
}
// case 1: {
// // relay.on(2);
// gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: debug mode 1!");
// in_debug_mode = 1;
// break;
// }
case 0: {
// relay.off(2);
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: debug mode off!");

1
ArduCopter/mode_auto.cpp

@ -448,6 +448,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) @@ -448,6 +448,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
break;
case MAV_CMD_NAV_LOITER_TURNS: //18 Loiter N Times
do_roi(cmd);
do_circle(cmd);
break;

2
ArduCopter/version.h

@ -6,7 +6,7 @@ @@ -6,7 +6,7 @@
#include "ap_version.h"
#define THISFIRMWARE "ZRUAV v4.0.8-RC1" //"ArduCopter V4.0.0"
#define THISFIRMWARE "ZRUAV v4.0.8-RC3" //"ArduCopter V4.0.0"
// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,0,8,FIRMWARE_VERSION_TYPE_OFFICIAL

7
ArduCopter/zr_flight.cpp

@ -75,14 +75,13 @@ void Copter::zr_SuperSlowLoop(){ @@ -75,14 +75,13 @@ void Copter::zr_SuperSlowLoop(){
camera.create_new_folder();
}
relay.on(3);
camera.set_in_arm_mode(true);
// camera.set_in_arm_mode(true);
}else{
relay.off(3);
camera.set_in_arm_mode(false);
// camera.set_in_arm_mode(false);
// rc().set_enable_ch();
updownStatus =UpDown_TakeOffStart;
updownStatus =UpDown_TakeOffStart;
}
if(before_fly){
uint8_t cnt,cacl_volt_pst;

20
libraries/AP_Camera/AP_Camera.cpp

@ -403,25 +403,7 @@ void AP_Camera::setup_feedback_callback(void) @@ -403,25 +403,7 @@ void AP_Camera::setup_feedback_callback(void)
_timer_installed = true;
}
}
void AP_Camera::set_in_arm_mode(bool state)
{
in_arm_mode = state;
}
bool AP_Camera::need_use_uavcan()
{
if(_trigger_type == AP_CAMERA_TRIGGER_TYPE_UAVCAN){
return true;
}
else{
if (!in_arm_mode){
return true;
}else{
return false;
}
}
return false;
}
// log_picture - log picture taken and send feedback to GCS
void AP_Camera::log_picture()
{

3
libraries/AP_Camera/AP_Camera.h

@ -130,8 +130,6 @@ public: @@ -130,8 +130,6 @@ public:
struct Camera_State &get_camera_state(){
return camera_state;
}
bool need_use_uavcan();
void set_in_arm_mode(bool state);
private:
static AP_Camera *_singleton;
@ -196,7 +194,6 @@ private: @@ -196,7 +194,6 @@ private:
char sver[12]; //software version
void send_can_msg(void);
bool in_arm_mode;
};
namespace AP {
AP_Camera *camera();

4
libraries/AP_UAVCAN/AP_UAVCAN.cpp

@ -924,8 +924,6 @@ void AP_UAVCAN::handle_zr_camera_status(AP_UAVCAN *ap_uavcan, uint8_t node_id, c @@ -924,8 +924,6 @@ void AP_UAVCAN::handle_zr_camera_status(AP_UAVCAN *ap_uavcan, uint8_t node_id, c
{
return;
}
if(!AP::camera()->need_use_uavcan())
return;
AP_Camera::Camera_State &interim_state = AP::camera()->get_camera_state();
interim_state.mode = cb.msg->mode;
interim_state.id = cb.msg->id;
@ -951,8 +949,6 @@ void AP_UAVCAN::handle_zr_camera_version(AP_UAVCAN *ap_uavcan, uint8_t node_id, @@ -951,8 +949,6 @@ void AP_UAVCAN::handle_zr_camera_version(AP_UAVCAN *ap_uavcan, uint8_t node_id,
{
return;
}
if(!AP::camera()->need_use_uavcan())
return;
char sn[15];
char ver[12];

Loading…
Cancel
Save