mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Rover: use enum class for ArmingMethod and ArmingRequired
This commit is contained in:
parent
ca7566fff9
commit
5bd0db4117
@ -282,7 +282,7 @@ void Rover::one_second_loop(void)
|
|||||||
// update notify flags
|
// update notify flags
|
||||||
AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);
|
AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);
|
||||||
AP_Notify::flags.pre_arm_gps_check = true;
|
AP_Notify::flags.pre_arm_gps_check = true;
|
||||||
AP_Notify::flags.armed = arming.is_armed() || arming.arming_required() == AP_Arming::NO;
|
AP_Notify::flags.armed = arming.is_armed() || arming.arming_required() == AP_Arming::Required::NO;
|
||||||
|
|
||||||
// cope with changes to mavlink system ID
|
// cope with changes to mavlink system ID
|
||||||
mavlink_system.sysid = g.sysid_this_mav;
|
mavlink_system.sysid = g.sysid_this_mav;
|
||||||
|
@ -607,7 +607,7 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_l
|
|||||||
case MAV_CMD_COMPONENT_ARM_DISARM:
|
case MAV_CMD_COMPONENT_ARM_DISARM:
|
||||||
if (is_equal(packet.param1, 1.0f)) {
|
if (is_equal(packet.param1, 1.0f)) {
|
||||||
// run pre_arm_checks and arm_checks and display failures
|
// run pre_arm_checks and arm_checks and display failures
|
||||||
if (rover.arm_motors(AP_Arming::MAVLINK)) {
|
if (rover.arm_motors(AP_Arming::Method::MAVLINK)) {
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
} else {
|
} else {
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
|
@ -137,7 +137,7 @@ void RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const aux_swi
|
|||||||
// arm or disarm the motors
|
// arm or disarm the motors
|
||||||
case ARMDISARM:
|
case ARMDISARM:
|
||||||
if (ch_flag == HIGH) {
|
if (ch_flag == HIGH) {
|
||||||
rover.arm_motors(AP_Arming::RUDDER);
|
rover.arm_motors(AP_Arming::Method::RUDDER);
|
||||||
} else if (ch_flag == LOW) {
|
} else if (ch_flag == LOW) {
|
||||||
rover.disarm_motors();
|
rover.disarm_motors();
|
||||||
}
|
}
|
||||||
|
@ -512,7 +512,7 @@ private:
|
|||||||
uint8_t check_digital_pin(uint8_t pin);
|
uint8_t check_digital_pin(uint8_t pin);
|
||||||
bool should_log(uint32_t mask);
|
bool should_log(uint32_t mask);
|
||||||
void change_arm_state(void);
|
void change_arm_state(void);
|
||||||
bool arm_motors(AP_Arming::ArmingMethod method);
|
bool arm_motors(AP_Arming::Method method);
|
||||||
bool disarm_motors(void);
|
bool disarm_motors(void);
|
||||||
bool is_boat() const;
|
bool is_boat() const;
|
||||||
|
|
||||||
|
@ -126,7 +126,7 @@ MAV_RESULT Rover::mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor
|
|||||||
|
|
||||||
// arm motors
|
// arm motors
|
||||||
if (!arming.is_armed()) {
|
if (!arming.is_armed()) {
|
||||||
arm_motors(AP_Arming::ArmingMethod::MOTORTEST);
|
arm_motors(AP_Arming::Method::MOTORTEST);
|
||||||
}
|
}
|
||||||
|
|
||||||
// disable failsafes
|
// disable failsafes
|
||||||
|
@ -42,8 +42,8 @@ void Rover::init_rc_in()
|
|||||||
void Rover::rudder_arm_disarm_check()
|
void Rover::rudder_arm_disarm_check()
|
||||||
{
|
{
|
||||||
// check if arming/disarm using rudder is allowed
|
// check if arming/disarm using rudder is allowed
|
||||||
AP_Arming::ArmingRudder arming_rudder = arming.get_rudder_arming_type();
|
const AP_Arming::RudderArming arming_rudder = arming.get_rudder_arming_type();
|
||||||
if (arming_rudder == AP_Arming::ARMING_RUDDER_DISABLED) {
|
if (arming_rudder == AP_Arming::RudderArming::IS_DISABLED) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -72,14 +72,14 @@ void Rover::rudder_arm_disarm_check()
|
|||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
// time to arm!
|
// time to arm!
|
||||||
arm_motors(AP_Arming::RUDDER);
|
arm_motors(AP_Arming::Method::RUDDER);
|
||||||
rudder_arm_timer = 0;
|
rudder_arm_timer = 0;
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
// not at full right rudder
|
// not at full right rudder
|
||||||
rudder_arm_timer = 0;
|
rudder_arm_timer = 0;
|
||||||
}
|
}
|
||||||
} else if ((arming_rudder == AP_Arming::ARMING_RUDDER_ARMDISARM) && !g2.motors.active()) {
|
} else if ((arming_rudder == AP_Arming::RudderArming::ARMDISARM) && !g2.motors.active()) {
|
||||||
// when armed and motor not active (not moving), full left rudder starts disarming counter
|
// when armed and motor not active (not moving), full left rudder starts disarming counter
|
||||||
if (channel_steer->get_control_in() < -4000) {
|
if (channel_steer->get_control_in() < -4000) {
|
||||||
const uint32_t now = millis();
|
const uint32_t now = millis();
|
||||||
|
@ -335,7 +335,7 @@ void Rover::change_arm_state(void)
|
|||||||
/*
|
/*
|
||||||
arm motors
|
arm motors
|
||||||
*/
|
*/
|
||||||
bool Rover::arm_motors(AP_Arming::ArmingMethod method)
|
bool Rover::arm_motors(AP_Arming::Method method)
|
||||||
{
|
{
|
||||||
if (!arming.arm(method)) {
|
if (!arming.arm(method)) {
|
||||||
AP_Notify::events.arming_failed = true;
|
AP_Notify::events.arming_failed = true;
|
||||||
|
Loading…
Reference in New Issue
Block a user