Test brushless motor with APM 2.5

Hi, I am new in this topic but I want to implement a WLAN remote control. I have a Turnigy Plush 60A and an Brushless motor. The ESC is connected to my APM 2.5 board. With the following code I wanted to initially test my hardware. Unfortunately the ESCs are just beeping very fast if I set a number with "hal.rcout->write(MOTOR_FL, 1300);" But what I wanted to see is some spinning. Is maybe someone more experienced with this topic. I am personally more familiar with Linux and C++ and wanted to get into RC hardware.

Greetings

// Motor numbers definitions
#define MOTOR_FL   2    // Front left    
#define MOTOR_FR   0    // Front right
#define MOTOR_BL   1    // back left
#define MOTOR_BR   3    // back right

// ArduPilot Hardware Abstraction Layer
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;

void setup() { 
  hal.rcout->set_freq(0xF, 50);
  hal.rcout->enable_mask(0xFF);
}

void loop() {
  hal.rcout->write(MOTOR_FL, 1300);
  hal.rcout->write(MOTOR_FR, 1300);
  hal.rcout->write(MOTOR_BL, 1300);
  hal.rcout->write(MOTOR_BR, 1300);
  
  hal.scheduler->delay(50);  //Wait 50ms 
}

AP_HAL_MAIN();

Got it, was studying the manual:
This code is working, for people interested in testing the motors:

#include <AP_InertialSensor.h>
#include <AP_Common.h>
#include <AP_Math.h>
#include <AP_Param.h>
#include <AP_Progmem.h>
#include <AP_ADC.h>
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <GCS_MAVLink.h>
#include <PID.h>

#include <Arduino.h>

// PID array (6 pids, two for each axis)
PID pids[6];
#define PID_PITCH_RATE 	0
#define PID_ROLL_RATE 	1
#define PID_PITCH_STAB 	2
#define PID_ROLL_STAB 	3
#define PID_YAW_RATE 	4
#define PID_YAW_STAB 	5

// Motor numbers definitions
#define MOTOR_FL   2    // Front left    
#define MOTOR_FR   0    // Front right
#define MOTOR_BL   1    // back left
#define MOTOR_BR   3    // back right

// Radio min/max values for each stick for my radio (worked out at beginning of article)
#define RC_THR_MIN   1070

// ArduPilot Hardware Abstraction Layer
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;

void setup() { 
  hal.console->println("Setup()\n");
  
  hal.rcout->set_freq(0xF, 490);
  hal.rcout->enable_mask(0xFF);
}

float throttle = RC_THR_MIN;

void loop() {
  hal.rcout->write(MOTOR_FL, throttle);
  hal.rcout->write(MOTOR_FR, throttle);
  hal.rcout->write(MOTOR_BL, throttle);
  hal.rcout->write(MOTOR_BR, throttle);
  
  hal.console->printf_P(PSTR("Current THR[%f]\n"), throttle);
  
  // serial bytes available?
  int bytesAvail = hal.console->available();
  
  if(bytesAvail > 0) {				// yes
      char ch = hal.console->read();
      if(ch == '+') {
          throttle += 100;
      }
      if(ch == '-') {
          throttle -= 100;
          if(throttle < RC_THR_MIN)
              throttle = RC_THR_MIN;
      }
  }
  
  hal.scheduler->delay(50);  //Wait 50ms 
}

AP_HAL_MAIN();