Browse Source

增加照片数不一致判断,待测试

mission-4.1.18
zbr 4 years ago
parent
commit
7312a0a936
  1. 26
      ArduCopter/APM_Config.h
  2. 2
      ArduCopter/AP_Arming.cpp
  3. 2
      copy.sh
  4. 24
      libraries/AP_Camera/AP_Camera.cpp
  5. 12
      libraries/AP_Camera/AP_Camera.h
  6. 10
      libraries/AP_UAVCAN/AP_UAVCAN.cpp

26
ArduCopter/APM_Config.h

@ -15,37 +15,37 @@ @@ -15,37 +15,37 @@
//#define AC_AVOID_ENABLED DISABLED // disable stop-at-fence library
//#define AC_OAPATHPLANNER_ENABLED DISABLED // disable path planning around obstacles
//#define AC_TERRAIN DISABLED // disable terrain library
//#define PARACHUTE DISABLED // disable parachute release to save 1k of flash
#define PARACHUTE DISABLED // disable parachute release to save 1k of flash
//#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
//#define OPTFLOW DISABLED // disable optical flow sensor to save 5K of flash space
//#define VISUAL_ODOMETRY_ENABLED DISABLED // disable visual odometry to save 2K of flash space
//#define FRSKY_TELEM_ENABLED DISABLED // disable FRSky telemetry
//#define ADSB_ENABLED DISABLED // disable ADSB support
#define FRSKY_TELEM_ENABLED DISABLED // disable FRSky telemetry
#define ADSB_ENABLED DISABLED // disable ADSB support
//#define PRECISION_LANDING DISABLED // disable precision landing using companion computer or IRLock sensor
//#define BEACON_ENABLED DISABLED // disable beacon support
//#define SPRAYER_ENABLED DISABLED // disable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
#define BEACON_ENABLED DISABLED // disable beacon support
#define SPRAYER_ENABLED DISABLED // disable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
//#define WINCH_ENABLED DISABLED // disable winch support
//#define GRIPPER_ENABLED DISABLED // disable gripper support
//#define RPM_ENABLED DISABLED // disable rotations per minute sensor support
#define GRIPPER_ENABLED DISABLED // disable gripper support
#define RPM_ENABLED DISABLED // disable rotations per minute sensor support
//#define MAGNETOMETER DISABLED // disable magnetometer support
//#define STATS_ENABLED DISABLED // disable statistics support
//#define MODE_ACRO_ENABLED DISABLED // disable acrobatic mode support
//#define MODE_AUTO_ENABLED DISABLED // disable auto mode support
//#define MODE_BRAKE_ENABLED DISABLED // disable brake mode support
//#define MODE_CIRCLE_ENABLED DISABLED // disable circle mode support
//#define MODE_DRIFT_ENABLED DISABLED // disable drift mode support
//#define MODE_FLIP_ENABLED DISABLED // disable flip mode support
#define MODE_DRIFT_ENABLED DISABLED // disable drift mode support
#define MODE_FLIP_ENABLED DISABLED // disable flip mode support
//#define MODE_FOLLOW_ENABLED DISABLED // disable follow mode support
//#define MODE_GUIDED_ENABLED DISABLED // disable guided mode support
//#define MODE_GUIDED_NOGPS_ENABLED DISABLED // disable guided/nogps mode support
//#define MODE_LOITER_ENABLED DISABLED // disable loiter mode support
//#define MODE_POSHOLD_ENABLED DISABLED // disable poshold mode support
//#define MODE_RTL_ENABLED DISABLED // disable rtl mode support
//#define MODE_SMARTRTL_ENABLED DISABLED // disable smartrtl mode support
//#define MODE_SPORT_ENABLED DISABLED // disable sport mode support
#define MODE_SMARTRTL_ENABLED DISABLED // disable smartrtl mode support
#define MODE_SPORT_ENABLED DISABLED // disable sport mode support
//#define MODE_SYSTEMID_ENABLED DISABLED // disable system ID mode support
//#define MODE_THROW_ENABLED DISABLED // disable throw mode support
//#define MODE_ZIGZAG_ENABLED DISABLED // disable zigzag mode support
#define MODE_THROW_ENABLED DISABLED // disable throw mode support
#define MODE_ZIGZAG_ENABLED DISABLED // disable zigzag mode support
//#define OSD_ENABLED DISABLED // disable on-screen-display support
//#define BUTTON_ENABLED DISABLED // disable button support

2
ArduCopter/AP_Arming.cpp

@ -370,7 +370,7 @@ bool AP_Arming_Copter::gps_checks(bool display_failure) @@ -370,7 +370,7 @@ bool AP_Arming_Copter::gps_checks(bool display_failure)
// warn about hdop separately - to prevent user confusion with no gps lock
if (copter.gps.get_hdop() > copter.g.gps_hdop_good) {
check_failed(ARMING_CHECK_GPS, display_failure, " GPS HDOP过高%d(需要%d)",copter.gps.get_hdop(),copter.g.gps_hdop_good); //High GPS HDOP
check_failed(ARMING_CHECK_GPS, display_failure, " GPS HDOP过高%d(需要%d)",copter.gps.get_hdop(),int(copter.g.gps_hdop_good)); //High GPS HDOP
AP_Notify::flags.pre_arm_gps_check = false;
return false;
}

2
copy.sh

@ -1,2 +1,2 @@ @@ -1,2 +1,2 @@
sudo cp ./build/Pixhawk4/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/zr-v4/wsl/zr-v4.0.8-rc2.px4
sudo cp ./build/Pixhawk4/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/zr-v4/wsl/quad-zr-v4.0.8-rc4.px4

24
libraries/AP_Camera/AP_Camera.cpp

@ -607,16 +607,28 @@ void AP_Camera::send_camera_zr_status(mavlink_channel_t chan) @@ -607,16 +607,28 @@ void AP_Camera::send_camera_zr_status(mavlink_channel_t chan)
feedback_gimbal,
feedback_format,
feedback_error_fixed,
camera_state.num1,
camera_state.num2,
camera_state.num3,
camera_state.num4,
camera_state.num5,
camera_state.num[0],
camera_state.num[1],
camera_state.num[2],
camera_state.num[3],
camera_state.num[4],
camera_state.trigger_num,
camera_state.temperature);
}
uint8_t AP_Camera::delt_pic_number()
{
uint8_t delt = 0;
uint16_t num = camera_state.num[0];
for (size_t i = 1; i < 5; i++)
{
delt = abs(num - camera_state.num[i]);
if(delt != 0){
break;
}
}
return delt;
}
void AP_Camera::create_new_folder()
{
#if HAL_WITH_UAVCAN

12
libraries/AP_Camera/AP_Camera.h

@ -75,7 +75,7 @@ public: @@ -75,7 +75,7 @@ public:
void update_zr_camera_version(void);
void send_camera_zr_status(mavlink_channel_t chan);
void create_new_folder();
uint8_t delt_pic_number();
static const struct AP_Param::GroupInfo var_info[];
// set if vehicle is in AUTO mode
@ -100,11 +100,11 @@ public: @@ -100,11 +100,11 @@ public:
struct Camera_State
{
float temperature;
uint16_t num1;
uint16_t num2;
uint16_t num3;
uint16_t num4;
uint16_t num5;
uint16_t num[5];
// uint16_t num2;
// uint16_t num3;
// uint16_t num4;
// uint16_t num5;
uint16_t trigger_num;
uint8_t instance; // the instance number of this Camera
uint8_t id;

10
libraries/AP_UAVCAN/AP_UAVCAN.cpp

@ -927,11 +927,11 @@ void AP_UAVCAN::handle_zr_camera_status(AP_UAVCAN *ap_uavcan, uint8_t node_id, c @@ -927,11 +927,11 @@ void AP_UAVCAN::handle_zr_camera_status(AP_UAVCAN *ap_uavcan, uint8_t node_id, c
AP_Camera::Camera_State &interim_state = AP::camera()->get_camera_state();
interim_state.mode = cb.msg->mode;
interim_state.id = cb.msg->id;
interim_state.num1 = (uint16_t)cb.msg->camera_photo_number[0];
interim_state.num2 = (uint16_t)cb.msg->camera_photo_number[1];
interim_state.num3 = (uint16_t)cb.msg->camera_photo_number[2];
interim_state.num4 = (uint16_t)cb.msg->camera_photo_number[3];
interim_state.num5 = (uint16_t)cb.msg->camera_photo_number[4];
interim_state.num[0] = (uint16_t)cb.msg->camera_photo_number[0];
interim_state.num[1] = (uint16_t)cb.msg->camera_photo_number[1];
interim_state.num[2] = (uint16_t)cb.msg->camera_photo_number[2];
interim_state.num[3] = (uint16_t)cb.msg->camera_photo_number[3];
interim_state.num[4] = (uint16_t)cb.msg->camera_photo_number[4];
interim_state.temperature = cb.msg->temperature;
interim_state.shutter_speed = cb.msg->shutter_speed;
interim_state.err_code = cb.msg->error_code;

Loading…
Cancel
Save