Browse Source

Sub: Added frame type BLUEROV to configure use with the new AP_MotorsBlueROV class.

mission-4.1.18
Rustom Jehangir 9 years ago committed by Andrew Tridgell
parent
commit
54fa879116
  1. 2
      ArduSub/APM_Config.h
  2. 2
      ArduSub/Copter.h
  3. 2
      ArduSub/GCS_Mavlink.cpp
  4. 2
      ArduSub/config.h
  5. 1
      ArduSub/defines.h

2
ArduSub/APM_Config.h

@ -5,7 +5,7 @@ @@ -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 QUAD_FRAME
#define FRAME_CONFIG BLUEROV
/* options:
* QUAD_FRAME
* TRI_FRAME

2
ArduSub/Copter.h

@ -311,6 +311,8 @@ private: @@ -311,6 +311,8 @@ private:
#define MOTOR_CLASS AP_MotorsSingle
#elif FRAME_CONFIG == COAX_FRAME
#define MOTOR_CLASS AP_MotorsCoax
#elif FRAME_CONFIG == BLUEROV
#define MOTOR_CLASS AP_MotorsBlueROV
#else
#error Unrecognised frame type
#endif

2
ArduSub/GCS_Mavlink.cpp

@ -92,6 +92,8 @@ NOINLINE void Copter::send_heartbeat(mavlink_channel_t chan) @@ -92,6 +92,8 @@ NOINLINE void Copter::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,
#elif (FRAME_CONFIG == BLUEROV)
MAV_TYPE_SUBMARINE,
#else
#error Unrecognised frame type
#endif

2
ArduSub/config.h

@ -88,6 +88,8 @@ @@ -88,6 +88,8 @@
# define FRAME_CONFIG_STRING "SINGLE"
#elif FRAME_CONFIG == COAX_FRAME
# define FRAME_CONFIG_STRING "COAX"
#elif FRAME_CONFIG == BLUEROV
# define FRAME_CONFIG_STRING "BLUEROV"
#else
# define FRAME_CONFIG_STRING "UNKNOWN"
#endif

1
ArduSub/defines.h

@ -79,6 +79,7 @@ enum aux_sw_func { @@ -79,6 +79,7 @@ enum aux_sw_func {
#define OCTA_QUAD_FRAME 7
#define SINGLE_FRAME 8
#define COAX_FRAME 9
#define BLUEROV 10
// HIL enumerations
#define HIL_MODE_DISABLED 0

Loading…
Cancel
Save