Skip to content

Commit 3bb3e61

Browse files
committed
Rover: make modes optional at compile-time
1 parent 51c77fe commit 3bb3e61

32 files changed

+464
-64
lines changed

Rover/AP_Arming.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -126,8 +126,10 @@ bool AP_Arming_Rover::arm(AP_Arming::Method method, const bool do_arming_checks)
126126
// Set the SmartRTL home location. If activated, SmartRTL will ultimately try to land at this point
127127
rover.g2.smart_rtl.set_home(true);
128128

129+
#if ROVER_MODE_SIMPLE_ENABLED
129130
// initialize simple mode heading
130131
rover.mode_simple.init_heading();
132+
#endif
131133

132134
// save home heading for use in sail vehicles
133135
rover.g2.windvane.record_home_heading();
@@ -147,10 +149,12 @@ bool AP_Arming_Rover::disarm(const AP_Arming::Method method, bool do_disarm_chec
147149
if (!AP_Arming::disarm(method, do_disarm_checks)) {
148150
return false;
149151
}
152+
#if ROVER_MODE_AUTO_ENABLED
150153
if (rover.control_mode != &rover.mode_auto) {
151154
// reset the mission on disarm if we are not in auto
152155
rover.mode_auto.mission.reset();
153156
}
157+
#endif
154158

155159
update_soft_armed();
156160

Rover/AP_ExternalControl_Rover.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88

99
#include "Rover.h"
1010

11+
#if ROVER_MODE_GUIDED_ENABLED
1112
/*
1213
set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw
1314
velocity is in earth frame, NED, m/s
@@ -39,5 +40,6 @@ bool AP_ExternalControl_Rover::ready_for_external_control()
3940
{
4041
return rover.control_mode->in_guided_mode() && rover.arming.is_armed();
4142
}
43+
#endif
4244

4345
#endif // AP_EXTERNAL_CONTROL_ENABLED

Rover/AP_ExternalControl_Rover.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,8 @@
1010
class AP_ExternalControl_Rover : public AP_ExternalControl
1111
{
1212
public:
13+
14+
#if ROVER_MODE_GUIDED_ENABLED
1315
/*
1416
Set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw.
1517
Velocity is in earth frame, NED [m/s].
@@ -21,6 +23,7 @@ class AP_ExternalControl_Rover : public AP_ExternalControl
2123
Sets the global position for loiter point
2224
*/
2325
bool set_global_position(const Location& loc) override WARN_IF_UNUSED;
26+
#endif
2427

2528
private:
2629
/*

Rover/GCS_Mavlink.cpp

Lines changed: 16 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -626,6 +626,7 @@ const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
626626
MAV_STREAM_TERMINATOR // must have this at end of stream_entries
627627
};
628628

629+
#if ROVER_MODE_GUIDED_ENABLED
629630
bool GCS_MAVLINK_Rover::handle_guided_request(AP_Mission::Mission_Command &cmd)
630631
{
631632
if (!rover.control_mode->in_guided_mode()) {
@@ -636,6 +637,7 @@ bool GCS_MAVLINK_Rover::handle_guided_request(AP_Mission::Mission_Command &cmd)
636637
// make any new wp uploaded instant (in case we are already in Guided mode)
637638
return rover.mode_guided.set_desired_location(cmd.content.location);
638639
}
640+
#endif // ROVER_MODE_GUIDED_ENABLED
639641

640642
MAV_RESULT GCS_MAVLINK_Rover::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
641643
{
@@ -668,19 +670,23 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in
668670
}
669671
return MAV_RESULT_ACCEPTED;
670672

673+
#if ROVER_MODE_GUIDED_ENABLED
671674
case MAV_CMD_DO_REPOSITION:
672675
return handle_command_int_do_reposition(packet);
676+
#endif
673677

674678
case MAV_CMD_DO_SET_REVERSE:
675679
// param1 : Direction (0=Forward, 1=Reverse)
676680
rover.control_mode->set_reversed(is_equal(packet.param1,1.0f));
677681
return MAV_RESULT_ACCEPTED;
678682

683+
#if ROVER_MODE_RTL_ENABLED
679684
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
680685
if (rover.set_mode(rover.mode_rtl, ModeReason::GCS_COMMAND)) {
681686
return MAV_RESULT_ACCEPTED;
682687
}
683688
return MAV_RESULT_FAILED;
689+
#endif
684690

685691
case MAV_CMD_DO_MOTOR_TEST:
686692
// param1 : motor sequence number (a number from 1 to max number of motors on the vehicle)
@@ -693,13 +699,15 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in
693699
static_cast<int16_t>(packet.param3),
694700
packet.param4);
695701

702+
#if ROVER_MODE_AUTO_ENABLED
696703
case MAV_CMD_MISSION_START:
697704
if (rover.set_mode(rover.mode_auto, ModeReason::GCS_COMMAND)) {
698705
return MAV_RESULT_ACCEPTED;
699706
}
700707
return MAV_RESULT_FAILED;
708+
#endif
701709

702-
#if AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED
710+
#if AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED && ROVER_MODE_GUIDED_ENABLED
703711
case MAV_CMD_NAV_SET_YAW_SPEED:
704712
send_received_message_deprecation_warning("MAV_CMD_NAV_SET_YAW_SPEED");
705713
return handle_command_nav_set_yaw_speed(packet, msg);
@@ -710,6 +718,7 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in
710718
}
711719
}
712720

721+
#if ROVER_MODE_GUIDED_ENABLED
713722
#if AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED
714723
MAV_RESULT GCS_MAVLINK_Rover::handle_command_nav_set_yaw_speed(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
715724
{
@@ -732,7 +741,7 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_nav_set_yaw_speed(const mavlink_com
732741
}
733742
return MAV_RESULT_ACCEPTED;
734743
}
735-
#endif
744+
#endif // AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED
736745

737746
MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_do_reposition(const mavlink_command_int_t &packet)
738747
{
@@ -773,11 +782,13 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_do_reposition(const mavlink_com
773782

774783
return MAV_RESULT_ACCEPTED;
775784
}
785+
#endif // ROVER_MODE_GUIDED_ENABLED
776786

777787
void GCS_MAVLINK_Rover::handle_message(const mavlink_message_t &msg)
778788
{
779789
switch (msg.msgid) {
780790

791+
#if ROVER_MODE_GUIDED_ENABLED
781792
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:
782793
handle_set_attitude_target(msg);
783794
break;
@@ -789,6 +800,7 @@ void GCS_MAVLINK_Rover::handle_message(const mavlink_message_t &msg)
789800
case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:
790801
handle_set_position_target_global_int(msg);
791802
break;
803+
#endif
792804

793805
default:
794806
GCS_MAVLINK::handle_message(msg);
@@ -802,6 +814,7 @@ void GCS_MAVLINK_Rover::handle_manual_control_axes(const mavlink_manual_control_
802814
manual_override(rover.channel_throttle, packet.z, 1000, 2000, tnow);
803815
}
804816

817+
#if ROVER_MODE_GUIDED_ENABLED
805818
void GCS_MAVLINK_Rover::handle_set_attitude_target(const mavlink_message_t &msg)
806819
{
807820
// decode packet
@@ -1054,6 +1067,7 @@ void GCS_MAVLINK_Rover::handle_set_position_target_global_int(const mavlink_mess
10541067
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, 0.0f);
10551068
}
10561069
}
1070+
#endif // ROVER_MODE_GUIDED_ENABLED
10571071

10581072
/*
10591073
handle a LANDING_TARGET command. The timestamp has been jitter corrected

Rover/GCS_Mavlink.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,9 @@ class GCS_MAVLINK_Rover : public GCS_MAVLINK
4343
private:
4444

4545
void handle_message(const mavlink_message_t &msg) override;
46+
#if ROVER_MODE_GUIDED_ENABLED
4647
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
48+
#endif
4749
bool try_send_message(enum ap_message id) override;
4850

4951
void handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow) override;

Rover/GCS_Rover.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,18 +11,26 @@ uint8_t GCS_Rover::sysid_this_mav() const
1111

1212
bool GCS_Rover::simple_input_active() const
1313
{
14+
#if ROVER_MODE_SIMPLE_ENABLED
1415
if (rover.control_mode != &rover.mode_simple) {
1516
return false;
1617
}
1718
return (rover.g2.simple_type == ModeSimple::Simple_InitialHeading);
19+
#else
20+
return false;
21+
#endif
1822
}
1923

2024
bool GCS_Rover::supersimple_input_active() const
2125
{
26+
#if ROVER_MODE_SIMPLE_ENABLED
2227
if (rover.control_mode != &rover.mode_simple) {
2328
return false;
2429
}
2530
return (rover.g2.simple_type == ModeSimple::Simple_CardinalDirections);
31+
#else
32+
return false;
33+
#endif
2634
}
2735

2836
void GCS_Rover::update_vehicle_sensor_status_flags(void)

Rover/Parameters.cpp

Lines changed: 30 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,23 @@
66
Rover parameter definitions
77
*/
88

9+
10+
#ifndef ROVER_INITIAL_MODE
11+
#if ROVER_MODE_MANUAL_ENABLED
12+
#define ROVER_INITIAL_MODE Mode::Number::MANUAL
13+
#else
14+
#define ROVER_INITIAL_MODE Mode::Number::HOLD
15+
#endif
16+
#endif
17+
18+
#ifndef ROVER_DEFAULT_RC_MODE
19+
#if ROVER_MODE_MANUAL_ENABLED
20+
#define ROVER_DEFAULT_RC_MODE Mode::Number::MANUAL
21+
#else
22+
#define ROVER_DEFAULT_RC_MODE Mode::Number::HOLD
23+
#endif
24+
#endif
25+
926
const AP_Param::Info Rover::var_info[] = {
1027
// @Param: FORMAT_VERSION
1128
// @DisplayName: Eeprom format version number
@@ -31,7 +48,7 @@ const AP_Param::Info Rover::var_info[] = {
3148
// @Description: This selects the mode to start in on boot. This is useful for when you want to start in AUTO mode on boot without a receiver. Usually used in combination with when AUTO_TRIGGER_PIN or AUTO_KICKSTART.
3249
// @CopyValuesFrom: MODE1
3350
// @User: Advanced
34-
GSCALAR(initial_mode, "INITIAL_MODE", (int8_t)Mode::Number::MANUAL),
51+
GSCALAR(initial_mode, "INITIAL_MODE", (uint8_t)ROVER_INITIAL_MODE),
3552

3653
// @Param: SYSID_THISMAV
3754
// @DisplayName: MAVLink system ID of this vehicle
@@ -176,38 +193,38 @@ const AP_Param::Info Rover::var_info[] = {
176193
// @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,6:Follow,7:Simple,8:Dock,9:Circle,10:Auto,11:RTL,12:SmartRTL,15:Guided
177194
// @User: Standard
178195
// @Description: Driving mode for switch position 1 (910 to 1230 and above 2049)
179-
GSCALAR(mode1, "MODE1", (int8_t)Mode::Number::MANUAL),
196+
GSCALAR(mode1, "MODE1", (uint8_t)ROVER_DEFAULT_RC_MODE),
180197

181198
// @Param: MODE2
182199
// @DisplayName: Mode2
183200
// @Description: Driving mode for switch position 2 (1231 to 1360)
184201
// @CopyValuesFrom: MODE1
185202
// @User: Standard
186-
GSCALAR(mode2, "MODE2", (int8_t)Mode::Number::MANUAL),
203+
GSCALAR(mode2, "MODE2", (uint8_t)ROVER_DEFAULT_RC_MODE),
187204

188205
// @Param: MODE3
189206
// @CopyFieldsFrom: MODE1
190207
// @DisplayName: Mode3
191208
// @Description: Driving mode for switch position 3 (1361 to 1490)
192-
GSCALAR(mode3, "MODE3", (int8_t)Mode::Number::MANUAL),
209+
GSCALAR(mode3, "MODE3", (uint8_t)ROVER_DEFAULT_RC_MODE),
193210

194211
// @Param: MODE4
195212
// @CopyFieldsFrom: MODE1
196213
// @DisplayName: Mode4
197214
// @Description: Driving mode for switch position 4 (1491 to 1620)
198-
GSCALAR(mode4, "MODE4", (int8_t)Mode::Number::MANUAL),
215+
GSCALAR(mode4, "MODE4", (uint8_t)ROVER_DEFAULT_RC_MODE),
199216

200217
// @Param: MODE5
201218
// @CopyFieldsFrom: MODE1
202219
// @DisplayName: Mode5
203220
// @Description: Driving mode for switch position 5 (1621 to 1749)
204-
GSCALAR(mode5, "MODE5", (int8_t)Mode::Number::MANUAL),
221+
GSCALAR(mode5, "MODE5", (uint8_t)ROVER_DEFAULT_RC_MODE),
205222

206223
// @Param: MODE6
207224
// @CopyFieldsFrom: MODE1
208225
// @DisplayName: Mode6
209226
// @Description: Driving mode for switch position 6 (1750 to 2049)
210-
GSCALAR(mode6, "MODE6", (int8_t)Mode::Number::MANUAL),
227+
GSCALAR(mode6, "MODE6", (uint8_t)ROVER_DEFAULT_RC_MODE),
211228

212229
// variables not in the g class which contain EEPROM saved variables
213230

@@ -352,9 +369,11 @@ const AP_Param::Info Rover::var_info[] = {
352369
GOBJECT(rpm_sensor, "RPM", AP_RPM),
353370
#endif
354371

372+
#if ROVER_MODE_AUTO_ENABLED
355373
// @Group: MIS_
356374
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
357375
GOBJECTN(mode_auto.mission, mission, "MIS_", AP_Mission),
376+
#endif
358377

359378
// @Group: RSSI_
360379
// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp
@@ -663,7 +682,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
663682
// @User: Advanced
664683
AP_GROUPINFO("MANUAL_OPTIONS", 53, ParametersG2, manual_options, 0),
665684

666-
#if MODE_DOCK_ENABLED == ENABLED
685+
#if ROVER_MODE_DOCK_ENABLED
667686
// @Group: DOCK
668687
// @Path: mode_dock.cpp
669688
AP_SUBGROUPPTR(mode_dock_ptr, "DOCK", 54, ParametersG2, ModeDock),
@@ -686,9 +705,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
686705
// @User: Standard
687706
AP_GROUPINFO("FS_GCS_TIMEOUT", 56, ParametersG2, fs_gcs_timeout, 5),
688707

708+
#if ROVER_MODE_CIRCLE_ENABLED
689709
// @Group: CIRC
690710
// @Path: mode_circle.cpp
691711
AP_SUBGROUPINFO(mode_circle, "CIRC", 57, ParametersG2, ModeCircle),
712+
#endif
692713

693714
AP_GROUPEND
694715
};
@@ -735,7 +756,7 @@ ParametersG2::ParametersG2(void)
735756
wheel_rate_control(wheel_encoder),
736757
attitude_control(),
737758
smart_rtl(),
738-
#if MODE_DOCK_ENABLED == ENABLED
759+
#if ROVER_MODE_DOCK_ENABLED
739760
mode_dock_ptr(&rover.mode_dock),
740761
#endif
741762
#if HAL_PROXIMITY_ENABLED

Rover/Parameters.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -340,7 +340,7 @@ class ParametersG2 {
340340
AP_Proximity proximity;
341341
#endif
342342

343-
#if MODE_DOCK_ENABLED == ENABLED
343+
#if ROVER_MODE_DOCK_ENABLED
344344
// we need a pointer to the mode for the G2 table
345345
class ModeDock *mode_dock_ptr;
346346
#endif
@@ -433,7 +433,9 @@ class ParametersG2 {
433433
// FS GCS timeout trigger time
434434
AP_Float fs_gcs_timeout;
435435

436+
#if ROVER_MODE_CIRCLE_ENABLED
436437
class ModeCircle mode_circle;
438+
#endif
437439
};
438440

439441
extern const AP_Param::Info var_info[];

0 commit comments

Comments
 (0)