Browse Source

Copter: integrate optflow_enable param move to optflow class

master
Randy Mackay 11 years ago
parent
commit
3201a8dbca
  1. 2
      ArduCopter/GCS_Mavlink.pde
  2. 7
      ArduCopter/sensors.pde
  3. 2
      ArduCopter/setup.pde
  4. 4
      ArduCopter/system.pde
  5. 11
      ArduCopter/test.pde

2
ArduCopter/GCS_Mavlink.pde

@ -153,7 +153,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan) @@ -153,7 +153,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
}
#if OPTFLOW == ENABLED
if (g.optflow_enabled) {
if (optflow.enabled()) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
}
#endif

7
ArduCopter/sensors.pde

@ -93,9 +93,14 @@ static void init_compass() @@ -93,9 +93,14 @@ static void init_compass()
static void init_optflow()
{
#if OPTFLOW == ENABLED
// exit immediately if not enabled
if (!optflow.enabled()) {
return;
}
// initialise sensor and display error on failure
optflow.init();
if (!optflow.healthy()) {
g.optflow_enabled = false;
cliSerial->print_P(PSTR("Failed to Init OptFlow\n"));
Log_Write_Error(ERROR_SUBSYSTEM_OPTFLOW,ERROR_CODE_FAILED_TO_INITIALISE);
}

2
ArduCopter/setup.pde

@ -386,7 +386,7 @@ void report_optflow() @@ -386,7 +386,7 @@ void report_optflow()
cliSerial->printf_P(PSTR("OptFlow\n"));
print_divider();
print_enabled(g.optflow_enabled);
print_enabled(optflow.enabled());
print_blanks(2);
#endif // OPTFLOW == ENABLED

4
ArduCopter/system.pde

@ -222,9 +222,7 @@ static void init_ardupilot() @@ -222,9 +222,7 @@ static void init_ardupilot()
pos_control.set_dt(MAIN_LOOP_SECONDS);
// init the optical flow sensor
if(g.optflow_enabled) {
init_optflow();
}
init_optflow();
// initialise inertial nav
inertial_nav.init();

11
ArduCopter/test.pde

@ -198,17 +198,18 @@ static int8_t @@ -198,17 +198,18 @@ static int8_t
test_optflow(uint8_t argc, const Menu::arg *argv)
{
#if OPTFLOW == ENABLED
if(g.optflow_enabled) {
cliSerial->printf_P(PSTR("man id: %d\t"),optflow.read_register(ADNS3080_PRODUCT_ID));
if(optflow.enabled()) {
cliSerial->printf_P(PSTR("dev id: %d\t"),(int)optflow.device_id());
print_hit_enter();
while(1) {
delay(200);
optflow.update();
const Vector2i& raw = optflow.raw();
cliSerial->printf_P(PSTR("dx:%d\t dy:%d\t squal:%d\n"),
optflow.dx,
optflow.dy,
optflow.surface_quality);
(int)raw.x,
(int)raw.y,
(int)optflow.quality());
if(cliSerial->available() > 0) {
return (0);

Loading…
Cancel
Save