Browse Source

几个小修复,RTLALT,esc,print...

þ#
mission-4.1.18
zbr 4 years ago committed by binsir
parent
commit
2e35fca55d
  1. 2
      ArduCopter/Parameters.h
  2. 2
      ArduCopter/esc_calibration.cpp
  3. 2
      libraries/AP_Camera/AP_Camera.cpp
  4. 2
      modules/mavlink

2
ArduCopter/Parameters.h

@ -419,7 +419,7 @@ public: @@ -419,7 +419,7 @@ public:
AP_Int16 throttle_behavior;
AP_Float pilot_takeoff_alt;
AP_Int16 rtl_altitude;
AP_Int32 rtl_altitude;
AP_Int16 rtl_speed_cms;
AP_Float rtl_cone_slope;
#if RANGEFINDER_ENABLED == ENABLED

2
ArduCopter/esc_calibration.cpp

@ -118,7 +118,7 @@ void Copter::esc_calibration_auto() @@ -118,7 +118,7 @@ void Copter::esc_calibration_auto()
// delay for 5 seconds while outputting pulses
uint32_t tstart = millis();
while (millis() - tstart < 5000) {
while (millis() - tstart < 3000) {
SRV_Channels::cork();
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
SRV_Channels::push();

2
libraries/AP_Camera/AP_Camera.cpp

@ -487,7 +487,7 @@ void AP_Camera::uavcan_pic() @@ -487,7 +487,7 @@ void AP_Camera::uavcan_pic()
//altitude_rel = current_loc.alt - ahrs.get_home().alt;
}
gcs().send_text(MAV_SEVERITY_INFO, "alt:%f", camera_can_msg.alt);
// gcs().send_text(MAV_SEVERITY_INFO, "alt:%f", camera_can_msg.alt);
camera_can_msg.pitch = ahrs.pitch_sensor * 1e-2f;
camera_can_msg.roll = ahrs.roll_sensor * 1e-2f;
camera_can_msg.yaw = ahrs.yaw_sensor * 1e-2f;

2
modules/mavlink

@ -1 +1 @@ @@ -1 +1 @@
Subproject commit 0013b46db8cb437b6ad77d736263597d90a2262d
Subproject commit 18cab6950986cd7b9b7a507ec35f3501d4a7e019
Loading…
Cancel
Save