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

Navigator: VTOL: enable weather vane in auto mode outside of mission #13761

Merged
merged 5 commits into from
Dec 28, 2019
Merged
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
2 changes: 1 addition & 1 deletion msg/position_setpoint.msg
Original file line number Diff line number Diff line change
Expand Up @@ -55,4 +55,4 @@ float32 acceptance_radius # navigation acceptance_radius if we're doing waypoi
float32 cruising_speed # the generally desired cruising speed (not a hard constraint)
float32 cruising_throttle # the generally desired cruising throttle (not a hard constraint)

bool allow_weather_vane # VTOL: allow (in mission mode) the weather vane feature that turns the nose into the wind
bool disable_weather_vane # VTOL: disable (in auto mode) the weather vane feature that turns the nose into the wind
2 changes: 1 addition & 1 deletion src/lib/flight_tasks/tasks/Auto/FlightTaskAuto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,7 +238,7 @@ bool FlightTaskAuto::_evaluateTriplets()

if (_ext_yaw_handler != nullptr) {
// activation/deactivation of weather vane is based on parameter WV_EN and setting of navigator (allow_weather_vane)
(_param_wv_en.get() && _sub_triplet_setpoint.get().current.allow_weather_vane) ? _ext_yaw_handler->activate() :
(_param_wv_en.get() && !_sub_triplet_setpoint.get().current.disable_weather_vane) ? _ext_yaw_handler->activate() :
_ext_yaw_handler->deactivate();
}

Expand Down
10 changes: 5 additions & 5 deletions src/modules/navigator/mission.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -688,9 +688,6 @@ Mission::set_mission_items()

position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();

// allow weather vane in mission
pos_sp_triplet->current.allow_weather_vane = true;

/* do takeoff before going to setpoint if needed and not already in takeoff */
/* in fixed-wing this whole block will be ignored and a takeoff item is always propagated */
if (do_need_vertical_takeoff() &&
Expand Down Expand Up @@ -773,7 +770,7 @@ Mission::set_mission_items()
!_navigator->get_land_detected()->landed) {

/* disable weathervane before front transition for allowing yaw to align */
pos_sp_triplet->current.allow_weather_vane = false;
pos_sp_triplet->current.disable_weather_vane = true;

/* set yaw setpoint to heading of VTOL_TAKEOFF wp against current position */
_mission_item.yaw = get_bearing_to_next_waypoint(
Expand All @@ -795,6 +792,9 @@ Mission::set_mission_items()
_navigator->get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING &&
!_navigator->get_land_detected()->landed) {

/* re-enable weather vane again after alignment */
pos_sp_triplet->current.disable_weather_vane = false;

/* check if the vtol_takeoff waypoint is on top of us */
if (do_need_move_to_takeoff()) {
new_work_item_type = WORK_ITEM_TYPE_TRANSITON_AFTER_TAKEOFF;
Expand Down Expand Up @@ -976,7 +976,7 @@ Mission::set_mission_items()
&& has_next_position_item) {

/* disable weathervane before front transition for allowing yaw to align */
pos_sp_triplet->current.allow_weather_vane = false;
pos_sp_triplet->current.disable_weather_vane = true;

new_work_item_type = WORK_ITEM_TYPE_ALIGN;

Expand Down