Browse Source

Sub: Add 'SimpleROV' frame configuration for 3/4-dof ROVs

mission-4.1.18
Rustom Jehangir 9 years ago committed by Andrew Tridgell
parent
commit
d628b0d022
  1. 1
      ArduSub/APM_Config.h
  2. 2
      ArduSub/GCS_Mavlink.cpp
  3. 2
      ArduSub/Parameters.cpp
  4. 2
      ArduSub/Sub.h
  5. 2
      ArduSub/config.h
  6. 1
      ArduSub/defines.h
  7. 2
      ArduSub/wscript

1
ArduSub/APM_Config.h

@ -10,6 +10,7 @@ @@ -10,6 +10,7 @@
* BLUEROV_FRAME
* VECTORED_FRAME
* VECTORED6DOF_FRAME
* SIMPLEROV_FRAME
*/
// uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards)

2
ArduSub/GCS_Mavlink.cpp

@ -95,7 +95,7 @@ NOINLINE void Sub::send_heartbeat(mavlink_channel_t chan) @@ -95,7 +95,7 @@ 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,
#elif (FRAME_CONFIG == BLUEROV_FRAME || FRAME_CONFIG == VECTORED_FRAME || FRAME_CONFIG == VECTORED6DOF_FRAME)
#elif (FRAME_CONFIG == BLUEROV_FRAME || FRAME_CONFIG == VECTORED_FRAME || FRAME_CONFIG == VECTORED6DOF_FRAME || FRAME_CONFIG == SIMPLEROV_FRAME )
MAV_TYPE_SUBMARINE,
#else
#error Unrecognised frame type

2
ArduSub/Parameters.cpp

@ -942,7 +942,7 @@ const AP_Param::Info Sub::var_info[] = { @@ -942,7 +942,7 @@ const AP_Param::Info Sub::var_info[] = {
GOBJECT(rally, "RALLY_", AP_Rally),
#endif
//#if (FRAME_CONFIG == VECTORED_FRAME || FRAME_CONFIG == BLUEROV_FRAME || FRAME_CONFIG == VECTORED6DOF_FRAME)
//#if (FRAME_CONFIG == VECTORED_FRAME || FRAME_CONFIG == BLUEROV_FRAME || FRAME_CONFIG == VECTORED6DOF_FRAME || FRAME_CONFIG == SIMPLEROV )
// @Group: MOT_
// @Path: ../libraries/AP_Motors/AP_Motors6DOF.cpp
GOBJECT(motors, "MOT_", AP_Motors6DOF),

2
ArduSub/Sub.h

@ -325,6 +325,8 @@ private: @@ -325,6 +325,8 @@ private:
#define MOTOR_CLASS AP_MotorsVectoredROV
#elif FRAME_CONFIG == VECTORED6DOF_FRAME
#define MOTOR_CLASS AP_MotorsVectored6DOF
#elif FRAME_CONFIG == SIMPLEROV_FRAME
#define MOTOR_CLASS AP_MotorsSimpleROV
#else
#error Unrecognised frame type

2
ArduSub/config.h

@ -72,6 +72,8 @@ @@ -72,6 +72,8 @@
# define FRAME_CONFIG_STRING "ROV_VECTORED_FRAME"
#elif FRAME_CONFIG == VECTORED6DOF_FRAME
# define FRAME_CONFIG_STRING "ROV_VECTORED6DOF_FRAME"
#elif FRAME_CONFIG == SIMPLEROV_FRAME
# define FRAME_CONFIG_STRING "ROV_SIMPLEROV_FRAME"
#else
# define FRAME_CONFIG_STRING "UNKNOWN"
#endif

1
ArduSub/defines.h

@ -88,6 +88,7 @@ enum aux_sw_func { @@ -88,6 +88,7 @@ enum aux_sw_func {
#define BLUEROV_FRAME 10
#define VECTORED_FRAME 11
#define VECTORED6DOF_FRAME 12
#define SIMPLEROV_FRAME 13
// HIL enumerations
#define HIL_MODE_DISABLED 0

2
ArduSub/wscript

@ -35,7 +35,7 @@ def build(bld): @@ -35,7 +35,7 @@ def build(bld):
)
frames = (
'bluerov','vectored','vectored6DOF',
'bluerov','vectored','vectored6DOF','simplerov'
)
for frame in frames:

Loading…
Cancel
Save