mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-19 02:23:58 +08:00
commander use const where possible
- this helps tease apart the various pieces of commander.
This commit is contained in:
@@ -34,6 +34,8 @@
|
||||
#ifndef COMMANDER_HPP_
|
||||
#define COMMANDER_HPP_
|
||||
|
||||
#include "state_machine_helper.h"
|
||||
|
||||
#include <controllib/blocks.hpp>
|
||||
#include <px4_module.h>
|
||||
#include <px4_module_params.h>
|
||||
@@ -90,14 +92,33 @@ private:
|
||||
// Subscriptions
|
||||
Subscription<mission_result_s> _mission_result_sub;
|
||||
|
||||
bool handle_command(vehicle_status_s *status, const safety_s *safety, vehicle_command_s *cmd,
|
||||
actuator_armed_s *armed, home_position_s *home, vehicle_global_position_s *global_pos,
|
||||
vehicle_local_position_s *local_pos, orb_advert_t *home_pub,
|
||||
orb_advert_t *command_ack_pub, bool *changed);
|
||||
bool handle_command(vehicle_status_s *status_local, const safety_s &safety_local, const vehicle_command_s &cmd,
|
||||
actuator_armed_s *armed_local, home_position_s *home, const vehicle_global_position_s &global_pos,
|
||||
const vehicle_local_position_s &local_pos, orb_advert_t *home_pub, orb_advert_t *command_ack_pub, bool *changed);
|
||||
|
||||
bool set_home_position(orb_advert_t &homePub, home_position_s &home,
|
||||
const vehicle_local_position_s &localPosition, const vehicle_global_position_s &globalPosition,
|
||||
bool set_alt_only_to_lpos_ref);
|
||||
bool set_home_position(orb_advert_t &homePub, home_position_s &home, const vehicle_local_position_s &localPosition,
|
||||
const vehicle_global_position_s &globalPosition, bool set_alt_only_to_lpos_ref);
|
||||
|
||||
// Set the main system state based on RC and override device inputs
|
||||
transition_result_t set_main_state(const vehicle_status_s &status, const vehicle_global_position_s &global_position,
|
||||
const vehicle_local_position_s &local_position, bool *changed);
|
||||
|
||||
// Enable override (manual reversion mode) on the system
|
||||
transition_result_t set_main_state_override_on(const vehicle_status_s &status_local, bool *changed);
|
||||
|
||||
// Set the system main state based on the current RC inputs
|
||||
transition_result_t set_main_state_rc(const vehicle_status_s &status_local,
|
||||
const vehicle_global_position_s &global_position, const vehicle_local_position_s &local_position, bool *changed);
|
||||
|
||||
void check_valid(const hrt_abstime ×tamp, const hrt_abstime &timeout, const bool valid_in, bool *valid_out,
|
||||
bool *changed);
|
||||
|
||||
bool check_posvel_validity(const bool data_valid, const float data_accuracy, const float required_accuracy,
|
||||
const hrt_abstime &data_timestamp_us, hrt_abstime *last_fail_time_us, hrt_abstime *probation_time_us, bool *valid_state,
|
||||
bool *validity_changed);
|
||||
|
||||
void reset_posvel_validity(const vehicle_global_position_s &global_position,
|
||||
const vehicle_local_position_s &local_position, bool *changed);
|
||||
|
||||
void mission_init();
|
||||
|
||||
|
||||
+135
-156
File diff suppressed because it is too large
Load Diff
@@ -459,8 +459,7 @@ bool StateMachineHelperTest::mainStateTransitionTest()
|
||||
current_status_flags.condition_auto_mission_available = true;
|
||||
|
||||
// Attempt transition
|
||||
transition_result_t result = main_state_transition(¤t_vehicle_status, test->to_state, main_state_prev,
|
||||
¤t_status_flags, ¤t_commander_state);
|
||||
transition_result_t result = main_state_transition(current_vehicle_status, test->to_state, main_state_prev, current_status_flags, ¤t_commander_state);
|
||||
|
||||
// Validate result of transition
|
||||
ut_compare(test->assertMsg, test->expected_transition_result, result);
|
||||
|
||||
@@ -393,8 +393,7 @@ bool is_safe(const struct safety_s *safety, const struct actuator_armed_s *armed
|
||||
}
|
||||
|
||||
transition_result_t
|
||||
main_state_transition(struct vehicle_status_s *status, main_state_t new_main_state, uint8_t &main_state_prev,
|
||||
vehicle_status_flags_s *status_flags, struct commander_state_s *internal_state)
|
||||
main_state_transition(const vehicle_status_s& status, const main_state_t new_main_state, uint8_t &main_state_prev, const vehicle_status_flags_s& status_flags, commander_state_s *internal_state)
|
||||
{
|
||||
// IMPORTANT: The assumption of callers of this function is that the execution of
|
||||
// this check if essentially "free". Therefore any runtime checking in here has to be
|
||||
@@ -415,8 +414,8 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
|
||||
case commander_state_s::MAIN_STATE_ALTCTL:
|
||||
|
||||
/* need at minimum altitude estimate */
|
||||
if (status_flags->condition_local_altitude_valid ||
|
||||
status_flags->condition_global_position_valid) {
|
||||
if (status_flags.condition_local_altitude_valid ||
|
||||
status_flags.condition_global_position_valid) {
|
||||
ret = TRANSITION_CHANGED;
|
||||
}
|
||||
|
||||
@@ -425,8 +424,8 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
|
||||
case commander_state_s::MAIN_STATE_POSCTL:
|
||||
|
||||
/* need at minimum local position estimate */
|
||||
if (status_flags->condition_local_position_valid ||
|
||||
status_flags->condition_global_position_valid) {
|
||||
if (status_flags.condition_local_position_valid ||
|
||||
status_flags.condition_global_position_valid) {
|
||||
ret = TRANSITION_CHANGED;
|
||||
}
|
||||
|
||||
@@ -435,7 +434,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
|
||||
case commander_state_s::MAIN_STATE_AUTO_LOITER:
|
||||
|
||||
/* need global position estimate */
|
||||
if (status_flags->condition_global_position_valid) {
|
||||
if (status_flags.condition_global_position_valid) {
|
||||
ret = TRANSITION_CHANGED;
|
||||
}
|
||||
|
||||
@@ -444,7 +443,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
|
||||
case commander_state_s::MAIN_STATE_AUTO_FOLLOW_TARGET:
|
||||
|
||||
/* FOLLOW only implemented in MC */
|
||||
if (status->is_rotary_wing) {
|
||||
if (status.is_rotary_wing) {
|
||||
ret = TRANSITION_CHANGED;
|
||||
}
|
||||
|
||||
@@ -453,8 +452,8 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
|
||||
case commander_state_s::MAIN_STATE_AUTO_MISSION:
|
||||
|
||||
/* need global position, home position, and a valid mission */
|
||||
if (status_flags->condition_global_position_valid &&
|
||||
status_flags->condition_auto_mission_available) {
|
||||
if (status_flags.condition_global_position_valid &&
|
||||
status_flags.condition_auto_mission_available) {
|
||||
|
||||
ret = TRANSITION_CHANGED;
|
||||
}
|
||||
@@ -464,7 +463,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
|
||||
case commander_state_s::MAIN_STATE_AUTO_RTL:
|
||||
|
||||
/* need global position and home position */
|
||||
if (status_flags->condition_global_position_valid && status_flags->condition_home_position_valid) {
|
||||
if (status_flags.condition_global_position_valid && status_flags.condition_home_position_valid) {
|
||||
ret = TRANSITION_CHANGED;
|
||||
}
|
||||
|
||||
@@ -474,7 +473,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
|
||||
case commander_state_s::MAIN_STATE_AUTO_LAND:
|
||||
|
||||
/* need local position */
|
||||
if (status_flags->condition_local_position_valid) {
|
||||
if (status_flags.condition_local_position_valid) {
|
||||
ret = TRANSITION_CHANGED;
|
||||
}
|
||||
|
||||
@@ -483,7 +482,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
|
||||
case commander_state_s::MAIN_STATE_AUTO_PRECLAND:
|
||||
|
||||
/* need local and global position, and precision land only implemented for multicopters */
|
||||
if (status_flags->condition_local_position_valid && status_flags->condition_global_position_valid && status->is_rotary_wing) {
|
||||
if (status_flags.condition_local_position_valid && status_flags.condition_global_position_valid && status.is_rotary_wing) {
|
||||
ret = TRANSITION_CHANGED;
|
||||
}
|
||||
|
||||
@@ -492,7 +491,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
|
||||
case commander_state_s::MAIN_STATE_OFFBOARD:
|
||||
|
||||
/* need offboard signal */
|
||||
if (!status_flags->offboard_control_signal_lost) {
|
||||
if (!status_flags.offboard_control_signal_lost) {
|
||||
|
||||
ret = TRANSITION_CHANGED;
|
||||
}
|
||||
@@ -1044,7 +1043,7 @@ void set_link_loss_nav_state(vehicle_status_s *status,
|
||||
&& status_flags->condition_global_position_valid && status_flags->condition_home_position_valid) {
|
||||
|
||||
uint8_t main_state_prev = 0;
|
||||
main_state_transition(status, commander_state_s::MAIN_STATE_AUTO_RTL, main_state_prev, status_flags, internal_state);
|
||||
main_state_transition(*status, commander_state_s::MAIN_STATE_AUTO_RTL, main_state_prev, *status_flags, internal_state);
|
||||
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTL;
|
||||
|
||||
} else if (link_loss_act == link_loss_actions_t::AUTO_LAND && status_flags->condition_local_position_valid) {
|
||||
|
||||
@@ -92,8 +92,7 @@ transition_result_t arming_state_transition(struct vehicle_status_s *status,
|
||||
hrt_abstime time_since_boot);
|
||||
|
||||
transition_result_t
|
||||
main_state_transition(struct vehicle_status_s *status, main_state_t new_main_state, uint8_t &main_state_prev,
|
||||
vehicle_status_flags_s *status_flags, struct commander_state_s *internal_state);
|
||||
main_state_transition(const vehicle_status_s& status, const main_state_t new_main_state, uint8_t &main_state_prev, const vehicle_status_flags_s& status_flags, commander_state_s *internal_state);
|
||||
|
||||
transition_result_t hil_state_transition(hil_state_t new_state, orb_advert_t status_pub, struct vehicle_status_s *current_status, orb_advert_t *mavlink_log_pub);
|
||||
|
||||
|
||||
Reference in New Issue
Block a user