Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adding Some Vehicle Modes #493

Open
wants to merge 7 commits into
base: develop
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -39,15 +39,25 @@ public enum VehicleMode implements DroneAttribute {
COPTER_AUTOTUNE(15, Type.TYPE_COPTER, "Autotune"),
COPTER_POSHOLD(16, Type.TYPE_COPTER, "PosHold"),
COPTER_BRAKE(17,Type.TYPE_COPTER,"Brake"),
COPTER_THROW(18,Type.TYPE_COPTER,"Throw"),
COPTER_AVOID_ADSB(19,Type.TYPE_COPTER,"Throw"),
COPTER_GUIDED_NOGPS(20,Type.TYPE_COPTER,"Throw"),
COPTER_SMART_RTL(21,Type.TYPE_COPTER,"SmartRTL"),
COPTER_FLOWHOLD(22,Type.TYPE_COPTER,"FollowHold"),
COPTER_FOLLOW(23,Type.TYPE_COPTER,"Follow"),
COPTER_ZIGZAG(24,Type.TYPE_COPTER,"ZigZag"),

ROVER_MANUAL(0, Type.TYPE_ROVER, "Manual"),
ROVER_ACRO(1, Type.TYPE_ROVER, "Acro"),
ROVER_LEARNING(2, Type.TYPE_ROVER, "Learning"),
ROVER_STEERING(3, Type.TYPE_ROVER, "Steering"),
ROVER_HOLD(4, Type.TYPE_ROVER, "Hold"),
ROVER_FOLLOW(6, Type.TYPE_ROVER, "Follow"),
ROVER_AUTO(10, Type.TYPE_ROVER, "Auto"),
ROVER_RTL(11, Type.TYPE_ROVER, "RTL"),
ROVER_GUIDED(15, Type.TYPE_ROVER, "Guided"),
ROVER_INITIALIZING(16, Type.TYPE_ROVER, "Initializing"),
ROVER_SMART_RTL(12, Type.TYPE_ROVER, "SmartRTL"),

UNKNOWN(-1, Type.TYPE_UNKNOWN, "Unknown");

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,18 +29,28 @@ public enum ApmModes {
ROTOR_RTL(6, "RTL",MAV_TYPE.MAV_TYPE_QUADROTOR),
ROTOR_CIRCLE(7, "Circle",MAV_TYPE.MAV_TYPE_QUADROTOR),
ROTOR_LAND(9, "Land",MAV_TYPE.MAV_TYPE_QUADROTOR),
ROTOR_TOY(11, "Drift",MAV_TYPE.MAV_TYPE_QUADROTOR),
ROTOR_DRIFT(11, "Drift",MAV_TYPE.MAV_TYPE_QUADROTOR),
ROTOR_SPORT(13, "Sport",MAV_TYPE.MAV_TYPE_QUADROTOR),
ROTOR_AUTOTUNE(15, "Autotune",MAV_TYPE.MAV_TYPE_QUADROTOR),
ROTOR_POSHOLD(16, "PosHold",MAV_TYPE.MAV_TYPE_QUADROTOR),
ROTOR_BRAKE(17,"Brake",MAV_TYPE.MAV_TYPE_QUADROTOR),
ROTOR_THROW(18,"Brake",MAV_TYPE.MAV_TYPE_QUADROTOR),
ROTOR_AVOID_ADSB(19,"Brake",MAV_TYPE.MAV_TYPE_QUADROTOR),
ROTOR_GUIDED_NOGPS(20,"Brake",MAV_TYPE.MAV_TYPE_QUADROTOR),
ROTOR_SMART_RTL(21,"SmartRTL",MAV_TYPE.MAV_TYPE_QUADROTOR),
ROTOR_FLOWHOLD(22,"Follow",MAV_TYPE.MAV_TYPE_QUADROTOR),
ROTOR_FOLLOW(23,"Follow",MAV_TYPE.MAV_TYPE_QUADROTOR),
ROTOR_ZIGZAG(24,"Follow",MAV_TYPE.MAV_TYPE_QUADROTOR),

ROVER_MANUAL(0, "MANUAL", MAV_TYPE.MAV_TYPE_GROUND_ROVER),
ROVER_ACRO(1, "ACRO", MAV_TYPE.MAV_TYPE_GROUND_ROVER),
ROVER_LEARNING(2, "LEARNING", MAV_TYPE.MAV_TYPE_GROUND_ROVER),
ROVER_STEERING(3, "STEERING", MAV_TYPE.MAV_TYPE_GROUND_ROVER),
ROVER_HOLD(4, "HOLD", MAV_TYPE.MAV_TYPE_GROUND_ROVER),
ROVER_FOLLOW(6, "FOLLOW", MAV_TYPE.MAV_TYPE_GROUND_ROVER),
ROVER_AUTO(10, "AUTO", MAV_TYPE.MAV_TYPE_GROUND_ROVER),
ROVER_RTL(11, "RTL", MAV_TYPE.MAV_TYPE_GROUND_ROVER),
ROVER_SMART_RTL(12, "SmartRTL", MAV_TYPE.MAV_TYPE_GROUND_ROVER),
ROVER_GUIDED(15, "GUIDED", MAV_TYPE.MAV_TYPE_GROUND_ROVER),
ROVER_INITIALIZING(16, "INITIALIZING", MAV_TYPE.MAV_TYPE_GROUND_ROVER),

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -172,13 +172,16 @@ public static VehicleMode getVehicleMode(ApmModes mode) {
case ROTOR_RTL:
return VehicleMode.COPTER_RTL;

case ROTOR_SMART_RTL:
return VehicleMode.COPTER_SMART_RTL;

case ROTOR_CIRCLE:
return VehicleMode.COPTER_CIRCLE;

case ROTOR_LAND:
return VehicleMode.COPTER_LAND;

case ROTOR_TOY:
case ROTOR_DRIFT:
return VehicleMode.COPTER_DRIFT;

case ROTOR_SPORT:
Expand All @@ -193,10 +196,31 @@ public static VehicleMode getVehicleMode(ApmModes mode) {
case ROTOR_BRAKE:
return VehicleMode.COPTER_BRAKE;

case ROTOR_THROW:
return VehicleMode.COPTER_THROW;

case ROTOR_AVOID_ADSB:
return VehicleMode.COPTER_AVOID_ADSB;

case ROTOR_GUIDED_NOGPS:
return VehicleMode.COPTER_GUIDED_NOGPS;

case ROTOR_FLOWHOLD:
return VehicleMode.COPTER_FOLLOW;

case ROTOR_FOLLOW:
return VehicleMode.COPTER_FOLLOW;

case ROTOR_ZIGZAG:
return VehicleMode.COPTER_FOLLOW;


case ROVER_MANUAL:
return VehicleMode.ROVER_MANUAL;

case ROVER_ACRO:
return VehicleMode.ROVER_ACRO;

case ROVER_LEARNING:
return VehicleMode.ROVER_LEARNING;

Expand All @@ -209,9 +233,15 @@ public static VehicleMode getVehicleMode(ApmModes mode) {
case ROVER_AUTO:
return VehicleMode.ROVER_AUTO;

case ROVER_FOLLOW:
return VehicleMode.ROVER_FOLLOW;

case ROVER_RTL:
return VehicleMode.ROVER_RTL;

case ROVER_SMART_RTL:
return VehicleMode.ROVER_SMART_RTL;

case ROVER_GUIDED:
return VehicleMode.ROVER_GUIDED;

Expand Down