mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 07:13:56 -04:00
Rover: use new AP_RangeFinder_analog class
This commit is contained in:
parent
44768c911f
commit
12d73a8662
@ -268,9 +268,7 @@ AP_HAL::AnalogSource * batt_curr_pin;
|
|||||||
// SONAR selection
|
// SONAR selection
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
//
|
//
|
||||||
ModeFilterInt16_Size5 sonar_mode_filter(2);
|
static AP_RangeFinder_analog sonar;
|
||||||
AP_HAL::AnalogSource *sonar_analog_source;
|
|
||||||
AP_RangeFinder_MaxsonarXL *sonar;
|
|
||||||
|
|
||||||
// relay support
|
// relay support
|
||||||
AP_Relay relay;
|
AP_Relay relay;
|
||||||
@ -401,8 +399,7 @@ static uint8_t receiver_rssi;
|
|||||||
// the time when the last HEARTBEAT message arrived from a GCS
|
// the time when the last HEARTBEAT message arrived from a GCS
|
||||||
static uint32_t last_heartbeat_ms;
|
static uint32_t last_heartbeat_ms;
|
||||||
|
|
||||||
// The distance as reported by Sonar in cm – Values are 20 to 700 generally.
|
// Set to true when an obstacle is detected
|
||||||
static int16_t sonar_dist_cm;
|
|
||||||
static bool obstacle = false;
|
static bool obstacle = false;
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
@ -580,16 +577,6 @@ void setup() {
|
|||||||
batt_volt_pin = hal.analogin->channel(g.battery_volt_pin);
|
batt_volt_pin = hal.analogin->channel(g.battery_volt_pin);
|
||||||
batt_curr_pin = hal.analogin->channel(g.battery_curr_pin);
|
batt_curr_pin = hal.analogin->channel(g.battery_curr_pin);
|
||||||
|
|
||||||
#if CONFIG_SONAR_SOURCE == SONAR_SOURCE_ADC
|
|
||||||
sonar_analog_source = new AP_ADC_AnalogSource(
|
|
||||||
&adc, CONFIG_SONAR_SOURCE_ADC_CHANNEL, 0.25);
|
|
||||||
#elif CONFIG_SONAR_SOURCE == SONAR_SOURCE_ANALOG_PIN
|
|
||||||
sonar_analog_source = hal.analogin->channel(
|
|
||||||
CONFIG_SONAR_SOURCE_ANALOG_PIN);
|
|
||||||
sonar = new AP_RangeFinder_MaxsonarXL(sonar_analog_source,
|
|
||||||
&sonar_mode_filter);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
init_ardupilot();
|
init_ardupilot();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -668,7 +655,7 @@ static void fast_loop()
|
|||||||
// Read Sonar
|
// Read Sonar
|
||||||
// ----------
|
// ----------
|
||||||
if (g.sonar_enabled) {
|
if (g.sonar_enabled) {
|
||||||
sonar_dist_cm = sonar->read();
|
float sonar_dist_cm = sonar.distance_cm();
|
||||||
if (sonar_dist_cm <= g.sonar_trigger_cm) {
|
if (sonar_dist_cm <= g.sonar_trigger_cm) {
|
||||||
// obstacle detected in front
|
// obstacle detected in front
|
||||||
obstacle = true;
|
obstacle = true;
|
||||||
|
@ -420,6 +420,14 @@ static void NOINLINE send_hwstatus(mavlink_channel_t chan)
|
|||||||
hal.i2c->lockup_count());
|
hal.i2c->lockup_count());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void NOINLINE send_rangefinder(mavlink_channel_t chan)
|
||||||
|
{
|
||||||
|
mavlink_msg_rangefinder_send(
|
||||||
|
chan,
|
||||||
|
sonar.distance_cm() * 0.01,
|
||||||
|
sonar.voltage());
|
||||||
|
}
|
||||||
|
|
||||||
static void NOINLINE send_current_waypoint(mavlink_channel_t chan)
|
static void NOINLINE send_current_waypoint(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
mavlink_msg_mission_current_send(
|
mavlink_msg_mission_current_send(
|
||||||
@ -584,6 +592,11 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
|
|||||||
send_hwstatus(chan);
|
send_hwstatus(chan);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSG_RANGEFINDER:
|
||||||
|
CHECK_PAYLOAD_SIZE(RANGEFINDER);
|
||||||
|
send_rangefinder(chan);
|
||||||
|
break;
|
||||||
|
|
||||||
case MSG_RETRY_DEFERRED:
|
case MSG_RETRY_DEFERRED:
|
||||||
break; // just here to prevent a warning
|
break; // just here to prevent a warning
|
||||||
}
|
}
|
||||||
@ -862,6 +875,7 @@ GCS_MAVLINK::data_stream_send(void)
|
|||||||
if (stream_trigger(STREAM_EXTRA3)) {
|
if (stream_trigger(STREAM_EXTRA3)) {
|
||||||
send_message(MSG_AHRS);
|
send_message(MSG_AHRS);
|
||||||
send_message(MSG_HWSTATUS);
|
send_message(MSG_HWSTATUS);
|
||||||
|
send_message(MSG_RANGEFINDER);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -98,6 +98,7 @@ public:
|
|||||||
|
|
||||||
// obstacle control
|
// obstacle control
|
||||||
k_param_sonar_enabled = 190,
|
k_param_sonar_enabled = 190,
|
||||||
|
k_param_sonar, // sonar object
|
||||||
k_param_sonar_type,
|
k_param_sonar_type,
|
||||||
k_param_sonar_trigger_cm,
|
k_param_sonar_trigger_cm,
|
||||||
k_param_sonar_turn_angle,
|
k_param_sonar_turn_angle,
|
||||||
|
@ -356,6 +356,10 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
GOBJECT(gcs0, "SR0_", GCS_MAVLINK),
|
GOBJECT(gcs0, "SR0_", GCS_MAVLINK),
|
||||||
GOBJECT(gcs3, "SR3_", GCS_MAVLINK),
|
GOBJECT(gcs3, "SR3_", GCS_MAVLINK),
|
||||||
|
|
||||||
|
// @Group: SONAR_
|
||||||
|
// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp
|
||||||
|
GOBJECT(sonar, "SONAR_", AP_RangeFinder_analog),
|
||||||
|
|
||||||
#if HIL_MODE == HIL_MODE_DISABLED
|
#if HIL_MODE == HIL_MODE_DISABLED
|
||||||
// @Group: INS_
|
// @Group: INS_
|
||||||
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
|
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
|
||||||
|
@ -122,6 +122,7 @@ enum ap_message {
|
|||||||
MSG_AHRS,
|
MSG_AHRS,
|
||||||
MSG_SIMSTATE,
|
MSG_SIMSTATE,
|
||||||
MSG_HWSTATUS,
|
MSG_HWSTATUS,
|
||||||
|
MSG_RANGEFINDER,
|
||||||
MSG_RETRY_DEFERRED // this must be last
|
MSG_RETRY_DEFERRED // this must be last
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -1,13 +1,12 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
|
||||||
static void init_sonar(void)
|
static void init_sonar(void)
|
||||||
{
|
{
|
||||||
/*
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||||
#if CONFIG_SONAR_SOURCE == SONAR_SOURCE_ADC
|
sonar.Init(&adc);
|
||||||
sonar.calculate_scaler(g.sonar_type, 3.3);
|
#else
|
||||||
#else
|
sonar.Init(NULL);
|
||||||
sonar.calculate_scaler(g.sonar_type, 5.0);
|
#endif
|
||||||
#endif
|
|
||||||
*/
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Sensors are not available in HIL_MODE_ATTITUDE
|
// Sensors are not available in HIL_MODE_ATTITUDE
|
||||||
|
@ -180,8 +180,10 @@ static void init_ardupilot()
|
|||||||
//compass.get_offsets(); // load offsets to account for airframe magnetic interference
|
//compass.get_offsets(); // load offsets to account for airframe magnetic interference
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// initialise sonar
|
// initialise sonar
|
||||||
init_sonar();
|
init_sonar();
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
// Do GPS init
|
// Do GPS init
|
||||||
g_gps = &g_gps_driver;
|
g_gps = &g_gps_driver;
|
||||||
|
@ -551,14 +551,14 @@ test_sonar(uint8_t argc, const Menu::arg *argv)
|
|||||||
}
|
}
|
||||||
|
|
||||||
print_hit_enter();
|
print_hit_enter();
|
||||||
delay(1000);
|
init_sonar();
|
||||||
init_sonar();
|
|
||||||
delay(1000);
|
|
||||||
|
|
||||||
while (true) {
|
while (true) {
|
||||||
delay(20);
|
delay(200);
|
||||||
sonar_dist_cm = sonar->read();
|
float sonar_dist_cm = sonar.distance_cm();
|
||||||
cliSerial->printf_P(PSTR("sonar distance = %u cm\n"), (unsigned)sonar_dist_cm);
|
float voltage = sonar.voltage();
|
||||||
|
cliSerial->printf_P(PSTR("sonar distance=%5.1fcm voltage=%5.2f\n"),
|
||||||
|
sonar_dist_cm, voltage);
|
||||||
if (cliSerial->available() > 0) {
|
if (cliSerial->available() > 0) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user