mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Sub: Separated motor files and frame types
This commit is contained in:
parent
321e92cf4c
commit
771ce2f607
@ -5,7 +5,7 @@
|
||||
// If you used to define your CONFIG_APM_HARDWARE setting here, it is no longer
|
||||
// valid! You should switch to using a HAL_BOARD flag in your local config.mk.
|
||||
|
||||
#define FRAME_CONFIG BLUEROV
|
||||
#define FRAME_CONFIG VECTORED_FRAME
|
||||
/* options:
|
||||
* QUAD_FRAME
|
||||
* TRI_FRAME
|
||||
@ -16,6 +16,8 @@
|
||||
* HELI_FRAME
|
||||
* SINGLE_FRAME
|
||||
* COAX_FRAME
|
||||
* BLUEROV_FRAME
|
||||
* VECTORED_FRAME
|
||||
*/
|
||||
|
||||
// uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards)
|
||||
|
@ -92,11 +92,8 @@ NOINLINE void Sub::send_heartbeat(mavlink_channel_t chan)
|
||||
MAV_TYPE_ROCKET,
|
||||
#elif (FRAME_CONFIG == COAX_FRAME) //because mavlink did not define a singlecopter, we use a rocket
|
||||
MAV_TYPE_ROCKET,
|
||||
<<<<<<< 6dafedb2d1ad5061d859a9c319fa4b69b4ac5dd9
|
||||
#elif (FRAME_CONFIG == BLUEROV)
|
||||
#elif (FRAME_CONFIG == BLUEROV_FRAME || FRAME_CONFIG == VECTORED_FRAME)
|
||||
MAV_TYPE_SUBMARINE,
|
||||
=======
|
||||
>>>>>>> Changed to ArduCopter as the base code.
|
||||
#else
|
||||
#error Unrecognised frame type
|
||||
#endif
|
||||
|
@ -162,11 +162,8 @@ private:
|
||||
RC_Channel *channel_pitch;
|
||||
RC_Channel *channel_throttle;
|
||||
RC_Channel *channel_yaw;
|
||||
<<<<<<< 6dafedb2d1ad5061d859a9c319fa4b69b4ac5dd9
|
||||
RC_Channel *channel_forward;
|
||||
RC_Channel *channel_strafe;
|
||||
=======
|
||||
>>>>>>> Changed to ArduCopter as the base code.
|
||||
|
||||
// Dataflash
|
||||
DataFlash_Class DataFlash{FIRMWARE_STRING};
|
||||
@ -316,11 +313,10 @@ private:
|
||||
#define MOTOR_CLASS AP_MotorsSingle
|
||||
#elif FRAME_CONFIG == COAX_FRAME
|
||||
#define MOTOR_CLASS AP_MotorsCoax
|
||||
<<<<<<< 6dafedb2d1ad5061d859a9c319fa4b69b4ac5dd9
|
||||
#elif FRAME_CONFIG == BLUEROV
|
||||
#define MOTOR_CLASS AP_MotorsBlueROV
|
||||
=======
|
||||
>>>>>>> Changed to ArduCopter as the base code.
|
||||
#elif FRAME_CONFIG == BLUEROV_FRAME
|
||||
#define MOTOR_CLASS AP_MotorsBlueROV6DOF
|
||||
#elif FRAME_CONFIG == VECTORED_FRAME
|
||||
#define MOTOR_CLASS AP_MotorsVectoredROV
|
||||
#else
|
||||
#error Unrecognised frame type
|
||||
#endif
|
||||
@ -818,11 +814,8 @@ private:
|
||||
void sport_run();
|
||||
bool stabilize_init(bool ignore_checks);
|
||||
void stabilize_run();
|
||||
<<<<<<< 6dafedb2d1ad5061d859a9c319fa4b69b4ac5dd9
|
||||
bool rov_init(bool ignore_checks);
|
||||
void rov_run();
|
||||
=======
|
||||
>>>>>>> Changed to ArduCopter as the base code.
|
||||
void crash_check();
|
||||
void parachute_check();
|
||||
void parachute_release();
|
||||
|
@ -88,11 +88,10 @@
|
||||
# define FRAME_CONFIG_STRING "SINGLE"
|
||||
#elif FRAME_CONFIG == COAX_FRAME
|
||||
# define FRAME_CONFIG_STRING "COAX"
|
||||
<<<<<<< 6dafedb2d1ad5061d859a9c319fa4b69b4ac5dd9
|
||||
#elif FRAME_CONFIG == BLUEROV
|
||||
# define FRAME_CONFIG_STRING "BLUEROV"
|
||||
=======
|
||||
>>>>>>> Changed to ArduCopter as the base code.
|
||||
#elif FRAME_CONFIG == BLUEROV_FRAME
|
||||
# define FRAME_CONFIG_STRING "ROV_BLUEROV_FRAME"
|
||||
#elif FRAME_CONFIG == VECTORED_FRAME
|
||||
# define FRAME_CONFIG_STRING "ROV_VECTORED_FRAME"
|
||||
#else
|
||||
# define FRAME_CONFIG_STRING "UNKNOWN"
|
||||
#endif
|
||||
|
@ -79,10 +79,8 @@ enum aux_sw_func {
|
||||
#define OCTA_QUAD_FRAME 7
|
||||
#define SINGLE_FRAME 8
|
||||
#define COAX_FRAME 9
|
||||
<<<<<<< 6dafedb2d1ad5061d859a9c319fa4b69b4ac5dd9
|
||||
#define BLUEROV 10
|
||||
=======
|
||||
>>>>>>> Changed to ArduCopter as the base code.
|
||||
#define BLUEROV_FRAME 10
|
||||
#define VECTORED_FRAME 11
|
||||
|
||||
// HIL enumerations
|
||||
#define HIL_MODE_DISABLED 0
|
||||
|
Loading…
Reference in New Issue
Block a user