Plane: updates for new AP_RangeFinder API

This commit is contained in:
Andrew Tridgell 2014-06-27 13:05:14 +10:00
parent e69a473315
commit 28e1449e8d
6 changed files with 12 additions and 18 deletions

View File

@ -308,7 +308,7 @@ static AP_HAL::AnalogSource *rssi_analog_source;
////////////////////////////////////////////////////////////////////////////////
// Sonar
////////////////////////////////////////////////////////////////////////////////
static AP_RangeFinder_analog sonar;
static RangeFinder sonar;
////////////////////////////////////////////////////////////////////////////////
// Relay

View File

@ -520,14 +520,14 @@ static void NOINLINE send_wind(mavlink_channel_t chan)
static void NOINLINE send_rangefinder(mavlink_channel_t chan)
{
if (!sonar.enabled()) {
if (!sonar.healthy()) {
// no sonar to report
return;
}
mavlink_msg_rangefinder_send(
chan,
sonar.distance_cm() * 0.01f,
sonar.voltage());
sonar.voltage_mv()*0.001f);
}
static void NOINLINE send_current_waypoint(mavlink_channel_t chan)

View File

@ -361,8 +361,8 @@ static void Log_Write_Sonar()
struct log_Sonar pkt = {
LOG_PACKET_HEADER_INIT(LOG_SONAR_MSG),
timestamp : hal.scheduler->millis(),
distance : sonar.distance_cm(),
voltage : sonar.voltage(),
distance : (float)sonar.distance_cm(),
voltage : sonar.voltage_mv()*0.001f,
baro_alt : barometer.get_altitude(),
groundspeed : gps.ground_speed(),
throttle : (uint8_t)(100 * channel_throttle->norm_output())

View File

@ -98,7 +98,7 @@ public:
k_param_ground_steer_dps,
k_param_rally_limit_km_old, //unused anymore -- just holding this index
k_param_hil_err_limit,
k_param_sonar,
k_param_sonar_old, // unused
k_param_log_bitmask,
k_param_BoardConfig,
k_param_rssi_range,
@ -115,6 +115,7 @@ public:
k_param_takeoff_rotate_speed,
k_param_takeoff_throttle_slewrate,
k_param_takeoff_throttle_max,
k_param_sonar,
// 100: Arming parameters
k_param_arming = 100,

View File

@ -863,9 +863,9 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
GOBJECT(relay, "RELAY_", AP_Relay),
// @Group: SONAR_
// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp
GOBJECT(sonar, "SONAR_", AP_RangeFinder_analog),
// @Group: SONAR
// @Path: ../libraries/AP_RangeFinder/RangeFinder.cpp
GOBJECT(sonar, "SONAR", RangeFinder),
// RC channel
//-----------

View File

@ -10,20 +10,13 @@ static void init_barometer(void)
static void init_sonar(void)
{
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
sonar.Init(&apm1_adc);
#else
sonar.Init(NULL);
#endif
sonar.init();
}
// read the sonars
static void read_sonars(void)
{
if (!sonar.enabled()) {
// this makes it possible to disable sonar at runtime
return;
}
sonar.update();
if (should_log(MASK_LOG_SONAR))
Log_Write_Sonar();