mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Commander: switch helper functions to pass by reference
This commit is contained in:
parent
0fa91f7cb0
commit
d97fba67e5
@ -822,7 +822,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
|
||||
const bool forced = (static_cast<int>(roundf(cmd.param2)) == 21196);
|
||||
|
||||
if (!forced) {
|
||||
if (!(_land_detector.landed || _land_detector.maybe_landed) && !is_ground_rover(&_status)) {
|
||||
if (!(_land_detector.landed || _land_detector.maybe_landed) && !is_ground_rover(_status)) {
|
||||
if (cmd_arms) {
|
||||
if (_armed.armed) {
|
||||
mavlink_log_warning(&_mavlink_log_pub, "Arming denied! Already armed");
|
||||
@ -1603,21 +1603,21 @@ Commander::run()
|
||||
/* update vehicle status to find out vehicle type (required for preflight checks) */
|
||||
_status.system_type = _param_mav_type.get();
|
||||
|
||||
if (is_rotary_wing(&_status) || is_vtol(&_status)) {
|
||||
if (is_rotary_wing(_status) || is_vtol(_status)) {
|
||||
_status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_ROTARY_WING;
|
||||
|
||||
} else if (is_fixed_wing(&_status)) {
|
||||
} else if (is_fixed_wing(_status)) {
|
||||
_status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_FIXED_WING;
|
||||
|
||||
} else if (is_ground_rover(&_status)) {
|
||||
} else if (is_ground_rover(_status)) {
|
||||
_status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_ROVER;
|
||||
|
||||
} else {
|
||||
_status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_UNKNOWN;
|
||||
}
|
||||
|
||||
_status.is_vtol = is_vtol(&_status);
|
||||
_status.is_vtol_tailsitter = is_vtol_tailsitter(&_status);
|
||||
_status.is_vtol = is_vtol(_status);
|
||||
_status.is_vtol_tailsitter = is_vtol_tailsitter(_status);
|
||||
|
||||
_boot_timestamp = hrt_absolute_time();
|
||||
|
||||
@ -1668,9 +1668,9 @@ Commander::run()
|
||||
if (!_armed.armed) {
|
||||
_status.system_type = _param_mav_type.get();
|
||||
|
||||
const bool is_rotary = is_rotary_wing(&_status) || (is_vtol(&_status) && _vtol_status.vtol_in_rw_mode);
|
||||
const bool is_fixed = is_fixed_wing(&_status) || (is_vtol(&_status) && !_vtol_status.vtol_in_rw_mode);
|
||||
const bool is_ground = is_ground_rover(&_status);
|
||||
const bool is_rotary = is_rotary_wing(_status) || (is_vtol(_status) && _vtol_status.vtol_in_rw_mode);
|
||||
const bool is_fixed = is_fixed_wing(_status) || (is_vtol(_status) && !_vtol_status.vtol_in_rw_mode);
|
||||
const bool is_ground = is_ground_rover(_status);
|
||||
|
||||
/* disable manual override for all systems that rely on electronic stabilization */
|
||||
if (is_rotary) {
|
||||
@ -1684,8 +1684,8 @@ Commander::run()
|
||||
}
|
||||
|
||||
/* set vehicle_status.is_vtol flag */
|
||||
_status.is_vtol = is_vtol(&_status);
|
||||
_status.is_vtol_tailsitter = is_vtol_tailsitter(&_status);
|
||||
_status.is_vtol = is_vtol(_status);
|
||||
_status.is_vtol_tailsitter = is_vtol_tailsitter(_status);
|
||||
|
||||
/* check and update system / component ID */
|
||||
_status.system_id = _param_mav_sys_id.get();
|
||||
@ -1890,7 +1890,7 @@ Commander::run()
|
||||
_status.vtol_fw_permanent_stab = _vtol_status.fw_permanent_stab;
|
||||
|
||||
/* Make sure that this is only adjusted if vehicle really is of type vtol */
|
||||
if (is_vtol(&_status)) {
|
||||
if (is_vtol(_status)) {
|
||||
|
||||
// Check if there has been any change while updating the flags
|
||||
const auto new_vehicle_type = _vtol_status.vtol_in_rw_mode ?
|
||||
|
||||
@ -82,45 +82,45 @@
|
||||
|
||||
#define BLINK_MSG_TIME 700000 // 3 fast blinks (in us)
|
||||
|
||||
bool is_multirotor(const struct vehicle_status_s *current_status)
|
||||
bool is_multirotor(const vehicle_status_s ¤t_status)
|
||||
{
|
||||
return ((current_status->system_type == VEHICLE_TYPE_QUADROTOR) ||
|
||||
(current_status->system_type == VEHICLE_TYPE_HEXAROTOR) ||
|
||||
(current_status->system_type == VEHICLE_TYPE_OCTOROTOR) ||
|
||||
(current_status->system_type == VEHICLE_TYPE_TRICOPTER));
|
||||
return ((current_status.system_type == VEHICLE_TYPE_QUADROTOR) ||
|
||||
(current_status.system_type == VEHICLE_TYPE_HEXAROTOR) ||
|
||||
(current_status.system_type == VEHICLE_TYPE_OCTOROTOR) ||
|
||||
(current_status.system_type == VEHICLE_TYPE_TRICOPTER));
|
||||
}
|
||||
|
||||
bool is_rotary_wing(const struct vehicle_status_s *current_status)
|
||||
bool is_rotary_wing(const vehicle_status_s ¤t_status)
|
||||
{
|
||||
return is_multirotor(current_status) || (current_status->system_type == VEHICLE_TYPE_HELICOPTER)
|
||||
|| (current_status->system_type == VEHICLE_TYPE_COAXIAL);
|
||||
return is_multirotor(current_status) || (current_status.system_type == VEHICLE_TYPE_HELICOPTER)
|
||||
|| (current_status.system_type == VEHICLE_TYPE_COAXIAL);
|
||||
}
|
||||
|
||||
bool is_vtol(const struct vehicle_status_s *current_status)
|
||||
bool is_vtol(const vehicle_status_s ¤t_status)
|
||||
{
|
||||
return (current_status->system_type == VEHICLE_TYPE_VTOL_DUOROTOR ||
|
||||
current_status->system_type == VEHICLE_TYPE_VTOL_QUADROTOR ||
|
||||
current_status->system_type == VEHICLE_TYPE_VTOL_TILTROTOR ||
|
||||
current_status->system_type == VEHICLE_TYPE_VTOL_RESERVED2 ||
|
||||
current_status->system_type == VEHICLE_TYPE_VTOL_RESERVED3 ||
|
||||
current_status->system_type == VEHICLE_TYPE_VTOL_RESERVED4 ||
|
||||
current_status->system_type == VEHICLE_TYPE_VTOL_RESERVED5);
|
||||
return (current_status.system_type == VEHICLE_TYPE_VTOL_DUOROTOR ||
|
||||
current_status.system_type == VEHICLE_TYPE_VTOL_QUADROTOR ||
|
||||
current_status.system_type == VEHICLE_TYPE_VTOL_TILTROTOR ||
|
||||
current_status.system_type == VEHICLE_TYPE_VTOL_RESERVED2 ||
|
||||
current_status.system_type == VEHICLE_TYPE_VTOL_RESERVED3 ||
|
||||
current_status.system_type == VEHICLE_TYPE_VTOL_RESERVED4 ||
|
||||
current_status.system_type == VEHICLE_TYPE_VTOL_RESERVED5);
|
||||
}
|
||||
|
||||
bool is_vtol_tailsitter(const struct vehicle_status_s *current_status)
|
||||
bool is_vtol_tailsitter(const vehicle_status_s ¤t_status)
|
||||
{
|
||||
return (current_status->system_type == VEHICLE_TYPE_VTOL_DUOROTOR ||
|
||||
current_status->system_type == VEHICLE_TYPE_VTOL_QUADROTOR);
|
||||
return (current_status.system_type == VEHICLE_TYPE_VTOL_DUOROTOR ||
|
||||
current_status.system_type == VEHICLE_TYPE_VTOL_QUADROTOR);
|
||||
}
|
||||
|
||||
bool is_fixed_wing(const struct vehicle_status_s *current_status)
|
||||
bool is_fixed_wing(const vehicle_status_s ¤t_status)
|
||||
{
|
||||
return current_status->system_type == VEHICLE_TYPE_FIXED_WING;
|
||||
return current_status.system_type == VEHICLE_TYPE_FIXED_WING;
|
||||
}
|
||||
|
||||
bool is_ground_rover(const struct vehicle_status_s *current_status)
|
||||
bool is_ground_rover(const vehicle_status_s ¤t_status)
|
||||
{
|
||||
return current_status->system_type == VEHICLE_TYPE_GROUND_ROVER;
|
||||
return current_status.system_type == VEHICLE_TYPE_GROUND_ROVER;
|
||||
}
|
||||
|
||||
static hrt_abstime blink_msg_end = 0; // end time for currently blinking LED message, 0 if no blink message
|
||||
|
||||
@ -50,12 +50,12 @@
|
||||
#include <drivers/drv_board_led.h>
|
||||
|
||||
|
||||
bool is_multirotor(const struct vehicle_status_s *current_status);
|
||||
bool is_rotary_wing(const struct vehicle_status_s *current_status);
|
||||
bool is_vtol(const struct vehicle_status_s *current_status);
|
||||
bool is_vtol_tailsitter(const struct vehicle_status_s *current_status);
|
||||
bool is_fixed_wing(const struct vehicle_status_s *current_status);
|
||||
bool is_ground_rover(const struct vehicle_status_s *current_status);
|
||||
bool is_multirotor(const vehicle_status_s ¤t_status);
|
||||
bool is_rotary_wing(const vehicle_status_s ¤t_status);
|
||||
bool is_vtol(const vehicle_status_s ¤t_status);
|
||||
bool is_vtol_tailsitter(const vehicle_status_s ¤t_status);
|
||||
bool is_fixed_wing(const vehicle_status_s ¤t_status);
|
||||
bool is_ground_rover(const vehicle_status_s ¤t_status);
|
||||
|
||||
int buzzer_init(void);
|
||||
void buzzer_deinit(void);
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user