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

commander delete GPS receiver checks and minor cleanup #8914

Merged
merged 7 commits into from
Feb 19, 2018
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: 0 additions & 2 deletions msg/vehicle_status_flags.msg
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,6 @@ bool condition_home_position_valid # indicates a valid home position (a valid
bool condition_local_position_valid # set to true by the commander app if the quality of the local position estimate is good enough to use for navigation
bool condition_local_velocity_valid # set to true by the commander app if the quality of the local horizontal velocity data is good enough to use for navigation
bool condition_local_altitude_valid
bool condition_airspeed_valid # set to true by the commander app if there is a valid airspeed measurement available
bool condition_power_input_valid # set if input power is valid

bool circuit_breaker_engaged_power_check
Expand All @@ -31,5 +30,4 @@ bool offboard_control_loss_timeout # true if offboard is lost for
bool rc_signal_found_once
bool rc_input_blocked # set if RC input should be ignored temporarily
bool vtol_transition_failure # Set to true if vtol transition failed
bool gps_failure # Set to true if a gps failure is detected
bool usb_connected # status of the USB power supply
5 changes: 2 additions & 3 deletions src/modules/commander/Commander.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,6 @@
#include <uORB/topics/geofence_result.h>
#include <uORB/topics/mission_result.h>
#include <uORB/topics/safety.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_local_position.h>
Expand Down Expand Up @@ -95,12 +94,12 @@ class Commander : public control::SuperBlock, public ModuleBase<Commander>

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, vehicle_attitude_s *attitude, orb_advert_t *home_pub,
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,
const vehicle_attitude_s &attitude, bool set_alt_only_to_lpos_ref);
bool set_alt_only_to_lpos_ref);

void mission_init();

Expand Down
44 changes: 0 additions & 44 deletions src/modules/commander/PreflightCheck.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -448,42 +448,6 @@ static bool airspeedCheck(orb_advert_t *mavlink_log_pub, bool optional, bool rep
return success;
}

static bool gnssCheck(orb_advert_t *mavlink_log_pub, bool report_fail, bool &lock_detected)
{
bool success = true;
lock_detected = false;
int gpsSub = orb_subscribe(ORB_ID(vehicle_gps_position));

//Wait up to 2000ms to allow the driver to detect a GNSS receiver module
px4_pollfd_struct_t fds[1];
fds[0].fd = gpsSub;
fds[0].events = POLLIN;

if (px4_poll(fds, 1, 2000) <= 0) {
success = false;

} else {
struct vehicle_gps_position_s gps;

if ((OK != orb_copy(ORB_ID(vehicle_gps_position), gpsSub, &gps)) ||
(hrt_elapsed_time(&gps.timestamp) > 1000000)) {
success = false;
} else if (gps.fix_type >= 3) {
lock_detected = true;
}
}

//Report failure to detect module
if (!success) {
if (report_fail) {
mavlink_log_critical(mavlink_log_pub, "PREFLIGHT FAIL: GPS RECEIVER MISSING");
}
}

orb_unsubscribe(gpsSub);
return success;
}

static bool ekf2Check(orb_advert_t *mavlink_log_pub, bool optional, bool report_fail, bool enforce_gps_required)
{
bool success = true; // start with a pass and change to a fail if any test fails
Expand Down Expand Up @@ -779,14 +743,6 @@ bool preflightCheck(orb_advert_t *mavlink_log_pub, bool checkSensors, bool check
}
}

/* ---- Global Navigation Satellite System receiver ---- */
if (checkGNSS) {
bool lock_detected = false;
if (!gnssCheck(mavlink_log_pub, reportFailures, lock_detected)) {
failed = true;
}
}

/* ---- Navigation EKF ---- */
// only check EKF2 data if EKF2 is selected as the estimator and GNSS checking is enabled
int32_t estimator_type;
Expand Down
Loading