// one_hz_loop - runs at 1Hz void Sub::one_hz_loop() { bool arm_check = arming.pre_arm_checks(false); ap.pre_arm_check = arm_check; AP_Notify::flags.pre_arm_check = arm_check; AP_Notify::flags.pre_arm_gps_check = position_ok(); if (should_log(MASK_LOG_ANY)) { Log_Write_Data(DATA_AP_STATE, ap.value); } if (!motors.armed()) { // make it possible to change ahrs orientation at runtime during initial config ahrs.set_orientation(); // set all throttle channel settings motors.set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max()); } // update assigned functions and enable auxiliary servos SRV_Channels::enable_aux_servos(); // update position controller alt limits update_poscon_alt_max(); // log terrain data terrain_logging(); }
// one_hz_loop - runs at 1Hz void Sub::one_hz_loop() { if (should_log(MASK_LOG_ANY)) { Log_Write_Data(DATA_AP_STATE, ap.value); } update_arming_checks(); if (!motors.armed()) { // make it possible to change ahrs orientation at runtime during initial config ahrs.set_orientation(); update_using_interlock(); // set all throttle channel settings motors.set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max()); } // update assigned functions and enable auxiliary servos SRV_Channels::enable_aux_servos(); check_usb_mux(); // update position controller alt limits update_poscon_alt_max(); // enable/disable raw gyro/accel logging ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW)); // log terrain data terrain_logging(); }
// one_hz_loop - runs at 1Hz void Copter::one_hz_loop() { if (should_log(MASK_LOG_ANY)) { Log_Write_Data(DATA_AP_STATE, ap.value); } arming.update(); if (!motors->armed()) { // make it possible to change ahrs orientation at runtime during initial config ahrs.update_orientation(); update_using_interlock(); // check the user hasn't updated the frame class or type motors->set_frame_class_and_type((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get()); #if FRAME_CONFIG != HELI_FRAME // set all throttle channel settings motors->set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max()); #endif } // update assigned functions and enable auxiliary servos SRV_Channels::enable_aux_servos(); // log terrain data terrain_logging(); #if ADSB_ENABLED == ENABLED adsb.set_is_flying(!ap.land_complete); #endif AP_Notify::flags.flying = !ap.land_complete; // update error mask of sensors and subsystems. The mask uses the // MAV_SYS_STATUS_* values from mavlink. If a bit is set then it // indicates that the sensor or subsystem is present but not // functioning correctly gcs().update_sensor_status_flags(); // init compass location for declination init_compass_location(); }
// one_hz_loop - runs at 1Hz void Copter::one_hz_loop() { if (should_log(MASK_LOG_ANY)) { Log_Write_Data(DATA_AP_STATE, ap.value); } update_arming_checks(); if (!motors.armed()) { // make it possible to change ahrs orientation at runtime during initial config ahrs.set_orientation(); update_using_interlock(); #if FRAME_CONFIG != HELI_FRAME // check the user hasn't updated the frame orientation motors.set_frame_orientation(g.frame_orientation); // set all throttle channel settings motors.set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max()); #endif } // update assigned functions and enable auxiliary servos RC_Channel_aux::enable_aux_servos(); check_usb_mux(); // update position controller alt limits update_poscon_alt_max(); // enable/disable raw gyro/accel logging ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW)); // log terrain data terrain_logging(); adsb.set_is_flying(!ap.land_complete); }