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

Introduce boat vehicle type #24310

Open
wants to merge 10 commits into
base: main
Choose a base branch
from
2 changes: 2 additions & 0 deletions msg/versioned/VehicleStatus.msg
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,8 @@ uint8 vehicle_type
uint8 VEHICLE_TYPE_ROTARY_WING = 0
uint8 VEHICLE_TYPE_FIXED_WING = 1
uint8 VEHICLE_TYPE_ROVER = 2
uint8 VEHICLE_TYPE_BOAT = 5
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Before we introduce the new type type here, let's discuss the meaning of this field, see #24367

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I agree with the points made. As is it currently stands, the code is a bit confusing what is what and these changes should clear it up.



uint8 FAILSAFE_DEFER_STATE_DISABLED = 0
uint8 FAILSAFE_DEFER_STATE_ENABLED = 1
Expand Down
20 changes: 17 additions & 3 deletions src/modules/commander/Commander.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -583,6 +583,16 @@ transition_result_t Commander::arm(arm_disarm_reason_t calling_reason, bool run_
return TRANSITION_DENIED;
}

if ((is_ground_vehicle(_vehicle_status))
&& !_failsafe_flags.manual_control_signal_lost && !_is_throttle_near_center) {

mavlink_log_critical(&_mavlink_log_pub, "Arming denied: throttle not centered\t");
events::send(events::ID("commander_arm_denied_throttle_not_centered"), {events::Log::Critical, events::LogInternal::Info},
"Arming denied: throttle not centered");
tune_negative(true);
return TRANSITION_DENIED;
}

} else if (calling_reason == arm_disarm_reason_t::stick_gesture
|| calling_reason == arm_disarm_reason_t::rc_switch
|| calling_reason == arm_disarm_reason_t::rc_button) {
Expand Down Expand Up @@ -1723,7 +1733,6 @@ void Commander::updateParameters()
&& _vtol_vehicle_status.vehicle_vtol_state != vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW);
const bool is_fixed = is_fixed_wing(_vehicle_status) || (is_vtol(_vehicle_status)
&& _vtol_vehicle_status.vehicle_vtol_state == vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW);
const bool is_ground = is_ground_vehicle(_vehicle_status);

/* disable manual override for all systems that rely on electronic stabilization */
if (is_rotary) {
Expand All @@ -1732,8 +1741,11 @@ void Commander::updateParameters()
} else if (is_fixed) {
_vehicle_status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_FIXED_WING;

} else if (is_ground) {
} else if (is_rover_type(_vehicle_status)) {
_vehicle_status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_ROVER;

} else if (is_boat_type(_vehicle_status)) {
_vehicle_status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_BOAT;
}

_vehicle_status.is_vtol = is_vtol(_vehicle_status);
Expand Down Expand Up @@ -2901,13 +2913,15 @@ void Commander::manualControlCheck()

_is_throttle_above_center = (manual_control_setpoint.throttle > 0.2f);
_is_throttle_low = (manual_control_setpoint.throttle < -0.8f);
_is_throttle_near_center = (fabsf(manual_control_setpoint.throttle) < 0.05f);

if (isArmed()) {
// Abort autonomous mode and switch to position mode if sticks are moved significantly
// but only if actually in air.
if (manual_control_setpoint.sticks_moving
&& !_vehicle_control_mode.flag_control_manual_enabled
&& (_vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING)
&& (_vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING
|| _vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_BOAT)
) {
bool override_enabled = false;

Expand Down
1 change: 1 addition & 0 deletions src/modules/commander/Commander.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -275,6 +275,7 @@ class Commander : public ModuleBase<Commander>, public ModuleParams

bool _is_throttle_above_center{false};
bool _is_throttle_low{false};
bool _is_throttle_near_center{false};

bool _arm_tune_played{false};
bool _have_taken_off_since_arming{false};
Expand Down
10 changes: 10 additions & 0 deletions src/modules/commander/commander_helper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,6 +122,16 @@ bool is_ground_vehicle(const vehicle_status_s &current_status)
return (current_status.system_type == VEHICLE_TYPE_BOAT || current_status.system_type == VEHICLE_TYPE_GROUND_ROVER);
}

bool is_rover_type(const vehicle_status_s &current_status)
{
return current_status.system_type == VEHICLE_TYPE_GROUND_ROVER;
}

bool is_boat_type(const vehicle_status_s &current_status)
{
return current_status.system_type == VEHICLE_TYPE_BOAT;
}

// End time for currently blinking LED message, 0 if no blink message
static hrt_abstime blink_msg_end = 0;
static int fd_leds{-1};
Expand Down
2 changes: 2 additions & 0 deletions src/modules/commander/commander_helper.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,8 @@ bool is_vtol(const vehicle_status_s &current_status);
bool is_vtol_tailsitter(const vehicle_status_s &current_status);
bool is_fixed_wing(const vehicle_status_s &current_status);
bool is_ground_vehicle(const vehicle_status_s &current_status);
bool is_rover_type(const vehicle_status_s &current_status);
bool is_boat_type(const vehicle_status_s &current_status);

int buzzer_init(void);
void buzzer_deinit(void);
Expand Down
5 changes: 3 additions & 2 deletions src/modules/navigator/mission_block.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -206,8 +206,9 @@ MissionBlock::is_mission_item_reached_or_completed()
_waypoint_position_reached = true;
}

} else if (_mission_item.nav_cmd == NAV_CMD_TAKEOFF
&& _navigator->get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROVER) {
} else if (_mission_item.nav_cmd == NAV_CMD_TAKEOFF &&
(_navigator->get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROVER
|| _navigator->get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_BOAT)) {
// Accept takeoff waypoint to be reached if the distance in 2D plane is within acceptance radius
if (dist_xy >= 0.0f && dist_xy <= _navigator->get_acceptance_radius()) {
_waypoint_position_reached = true;
Expand Down
3 changes: 2 additions & 1 deletion src/modules/navigator/navigator_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1137,7 +1137,8 @@ float Navigator::get_altitude_acceptance_radius()
return _param_nav_fw_alt_rad.get();
}

} else if (get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROVER) {
} else if (get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROVER
|| get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_BOAT) {
return INFINITY;

} else {
Expand Down
Loading