mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 20:28:37 +08:00
Fix landing gear processing
This commit is contained in:
@@ -32,12 +32,6 @@
|
|||||||
****************************************************************************/
|
****************************************************************************/
|
||||||
|
|
||||||
#include "ManualControl.hpp"
|
#include "ManualControl.hpp"
|
||||||
|
|
||||||
#include <drivers/drv_hrt.h>
|
|
||||||
#include <commander/px4_custom_mode.h>
|
|
||||||
#include <uORB/topics/vehicle_command.h>
|
|
||||||
#include <uORB/topics/landing_gear.h>
|
|
||||||
#include <uORB/topics/vtol_vehicle_status.h>
|
|
||||||
#include <uORB/topics/commander_state.h>
|
#include <uORB/topics/commander_state.h>
|
||||||
|
|
||||||
namespace manual_control
|
namespace manual_control
|
||||||
@@ -201,10 +195,10 @@ void ManualControl::Run()
|
|||||||
&& _previous_switches.gear_switch != manual_control_switches_s::SWITCH_POS_NONE) {
|
&& _previous_switches.gear_switch != manual_control_switches_s::SWITCH_POS_NONE) {
|
||||||
|
|
||||||
if (switches.gear_switch == manual_control_switches_s::SWITCH_POS_ON) {
|
if (switches.gear_switch == manual_control_switches_s::SWITCH_POS_ON) {
|
||||||
publish_landing_gear(landing_gear_s::GEAR_UP);
|
publishLandingGear(landing_gear_s::GEAR_UP);
|
||||||
|
|
||||||
} else if (switches.gear_switch == manual_control_switches_s::SWITCH_POS_OFF) {
|
} else if (switches.gear_switch == manual_control_switches_s::SWITCH_POS_OFF) {
|
||||||
publish_landing_gear(landing_gear_s::GEAR_DOWN);
|
publishLandingGear(landing_gear_s::GEAR_DOWN);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -335,13 +329,12 @@ void ManualControl::sendActionRequest(int8_t action, int8_t source, int8_t mode)
|
|||||||
_action_request_pub.publish(action_request);
|
_action_request_pub.publish(action_request);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ManualControl::publish_landing_gear(int8_t action)
|
void ManualControl::publishLandingGear(int8_t action)
|
||||||
{
|
{
|
||||||
landing_gear_s landing_gear{};
|
landing_gear_s landing_gear{};
|
||||||
landing_gear.landing_gear = action;
|
landing_gear.landing_gear = action;
|
||||||
landing_gear.timestamp = hrt_absolute_time();
|
landing_gear.timestamp = hrt_absolute_time();
|
||||||
uORB::Publication<landing_gear_s> landing_gear_pub{ORB_ID(landing_gear)};
|
_landing_gear_pub.publish(landing_gear);
|
||||||
landing_gear_pub.publish(landing_gear);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int ManualControl::task_spawn(int argc, char *argv[])
|
int ManualControl::task_spawn(int argc, char *argv[])
|
||||||
|
|||||||
@@ -33,14 +33,16 @@
|
|||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include <drivers/drv_hrt.h>
|
||||||
|
#include <lib/hysteresis/hysteresis.h>
|
||||||
|
#include <lib/perf/perf_counter.h>
|
||||||
#include <px4_platform_common/defines.h>
|
#include <px4_platform_common/defines.h>
|
||||||
#include <px4_platform_common/module.h>
|
#include <px4_platform_common/module.h>
|
||||||
#include <px4_platform_common/module_params.h>
|
#include <px4_platform_common/module_params.h>
|
||||||
#include <px4_platform_common/posix.h>
|
#include <px4_platform_common/posix.h>
|
||||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
||||||
#include <lib/hysteresis/hysteresis.h>
|
|
||||||
#include <lib/perf/perf_counter.h>
|
|
||||||
#include <uORB/topics/action_request.h>
|
#include <uORB/topics/action_request.h>
|
||||||
|
#include <uORB/topics/landing_gear.h>
|
||||||
#include <uORB/topics/manual_control_input.h>
|
#include <uORB/topics/manual_control_input.h>
|
||||||
#include <uORB/topics/manual_control_switches.h>
|
#include <uORB/topics/manual_control_switches.h>
|
||||||
#include <uORB/topics/manual_control_setpoint.h>
|
#include <uORB/topics/manual_control_setpoint.h>
|
||||||
@@ -122,9 +124,10 @@ private:
|
|||||||
|
|
||||||
void evaluateModeSlot(uint8_t mode_slot);
|
void evaluateModeSlot(uint8_t mode_slot);
|
||||||
void sendActionRequest(int8_t action, int8_t source, int8_t mode = 0);
|
void sendActionRequest(int8_t action, int8_t source, int8_t mode = 0);
|
||||||
void publish_landing_gear(int8_t action);
|
void publishLandingGear(int8_t action);
|
||||||
|
|
||||||
uORB::Publication<action_request_s> _action_request_pub{ORB_ID(action_request)};
|
uORB::Publication<action_request_s> _action_request_pub{ORB_ID(action_request)};
|
||||||
|
uORB::Publication<landing_gear_s> _landing_gear_pub{ORB_ID(landing_gear)};
|
||||||
uORB::Publication<manual_control_setpoint_s> _manual_control_setpoint_pub{ORB_ID(manual_control_setpoint)};
|
uORB::Publication<manual_control_setpoint_s> _manual_control_setpoint_pub{ORB_ID(manual_control_setpoint)};
|
||||||
|
|
||||||
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
|
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
|
||||||
|
|||||||
@@ -154,7 +154,7 @@ MulticopterRateControl::Run()
|
|||||||
|
|
||||||
if (_landing_gear_sub.copy(&landing_gear)) {
|
if (_landing_gear_sub.copy(&landing_gear)) {
|
||||||
if (landing_gear.landing_gear != landing_gear_s::GEAR_KEEP) {
|
if (landing_gear.landing_gear != landing_gear_s::GEAR_KEEP) {
|
||||||
if (landing_gear_s::GEAR_UP && (_landed || _maybe_landed)) {
|
if (landing_gear.landing_gear == landing_gear_s::GEAR_UP && (_landed || _maybe_landed)) {
|
||||||
mavlink_log_critical(&_mavlink_log_pub, "Landed, unable to retract landing gear")
|
mavlink_log_critical(&_mavlink_log_pub, "Landed, unable to retract landing gear")
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
|
|||||||
Reference in New Issue
Block a user