Browse Source

兼容旧的声呐,改Rangefinder NMEA串口通信

zr_rover4.2
zbr 4 years ago
parent
commit
d1c9aed9ea
  1. 2
      APMrover2/version.cpp
  2. 6
      libraries/AP_RangeFinder/AP_RangeFinder_NMEA.cpp

2
APMrover2/version.cpp

@ -29,7 +29,7 @@ const AP_FWVersion AP_FWVersion::fwver{ @@ -29,7 +29,7 @@ const AP_FWVersion AP_FWVersion::fwver{
.fw_hash_str = "",
#else
// .fw_string = THISFIRMWARE " (" GIT_VERSION ")",
.fw_string = "Version: v4.0.2 ,Board ID:BD202103001",
.fw_string = "Version: v4.0.3 ,Board ID:BD202103001",
.fw_hash_str = GIT_VERSION,
#endif
.middleware_name = nullptr,

6
libraries/AP_RangeFinder/AP_RangeFinder_NMEA.cpp

@ -18,7 +18,7 @@ @@ -18,7 +18,7 @@
#include <AP_SerialManager/AP_SerialManager.h>
#include <ctype.h>
#include "AP_RangeFinder_NMEA.h"
// #include <GCS_MAVLink/GCS.h>
extern const AP_HAL::HAL& hal;
// constructor initialises the rangefinder
@ -50,6 +50,8 @@ void AP_RangeFinder_NMEA::update(void) @@ -50,6 +50,8 @@ void AP_RangeFinder_NMEA::update(void)
if (get_reading(state.distance_cm)) {
// update range_valid state based on distance measured
state.last_reading_ms = now;
// gcs().send_text(MAV_SEVERITY_INFO,"t:%ld,dist:%dcm",state.last_reading_ms,state.distance_cm);
update_status();
} else if ((now - state.last_reading_ms) > 3000) {
set_status(RangeFinder::RangeFinder_NoData);
@ -71,6 +73,8 @@ bool AP_RangeFinder_NMEA::get_reading(uint16_t &reading_cm) @@ -71,6 +73,8 @@ bool AP_RangeFinder_NMEA::get_reading(uint16_t &reading_cm)
ret = true;
_sonar_deep = radar_data[1];
_sonar_voltage = radar_data[5];
// gcs().send_text(MAV_SEVERITY_INFO,"deep:%.2f,volt:%.2f",_sonar_deep,_sonar_voltage);
}
}

Loading…
Cancel
Save