Skip to content

Commit

Permalink
manual_control_setpoint split switches into new manual_control_switches
Browse files Browse the repository at this point in the history
  • Loading branch information
dagar committed Nov 9, 2018
1 parent 8d15da3 commit a233853
Show file tree
Hide file tree
Showing 15 changed files with 245 additions and 180 deletions.
1 change: 1 addition & 0 deletions msg/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ set(msg_files
led_control.msg
log_message.msg
manual_control_setpoint.msg
manual_control_switches.msg
mavlink_log.msg
mission.msg
mission_result.msg
Expand Down
33 changes: 7 additions & 26 deletions msg/manual_control_setpoint.msg
Original file line number Diff line number Diff line change
@@ -1,23 +1,13 @@
uint64 timestamp # time since system start (microseconds)

uint8 SWITCH_POS_NONE = 0 # switch is not mapped
uint8 SWITCH_POS_ON = 1 # switch activated (value = 1)
uint8 SWITCH_POS_MIDDLE = 2 # middle position (value = 0)
uint8 SWITCH_POS_OFF = 3 # switch not activated (value = -1)
int8 MODE_SLOT_NONE = -1 # no mode slot assigned
int8 MODE_SLOT_1 = 0 # mode slot 1 selected
int8 MODE_SLOT_2 = 1 # mode slot 2 selected
int8 MODE_SLOT_3 = 2 # mode slot 3 selected
int8 MODE_SLOT_4 = 3 # mode slot 4 selected
int8 MODE_SLOT_5 = 4 # mode slot 5 selected
int8 MODE_SLOT_6 = 5 # mode slot 6 selected
int8 MODE_SLOT_MAX = 6 # number of slots plus one
uint8 SOURCE_RC = 1 # radio control
uint8 SOURCE_MAVLINK_0 = 2 # mavlink instance 0
uint8 SOURCE_MAVLINK_1 = 3 # mavlink instance 1
uint8 SOURCE_MAVLINK_2 = 4 # mavlink instance 2
uint8 SOURCE_MAVLINK_3 = 5 # mavlink instance 4

uint64 timestamp_last_signal # last valid reception time

# Any of the channels may not be available and be set to NaN
# to indicate that it does not contain valid data.
# The variable names follow the definition of the
Expand All @@ -30,37 +20,28 @@ float32 x # stick position in x direction -1..1
# in general corresponds to forward/back motion or pitch of vehicle,
# in general a positive value means forward or negative pitch and
# a negative value means backward or positive pitch

float32 y # stick position in y direction -1..1
# in general corresponds to right/left motion or roll of vehicle,
# in general a positive value means right or positive roll and
# a negative value means left or negative roll

float32 z # throttle stick position 0..1
# in general corresponds to up/down motion or thrust of vehicle,
# in general the value corresponds to the demanded throttle by the user,
# if the input is used for setting the setpoint of a vertical position
# controller any value > 0.5 means up and any value < 0.5 means down

float32 r # yaw stick/twist position, -1..1
# in general corresponds to the righthand rotation around the vertical
# (downwards) axis of the vehicle

float32 flaps # flap position

float32 aux1 # default function: camera yaw / azimuth
float32 aux2 # default function: camera pitch / tilt
float32 aux3 # default function: camera trigger
float32 aux4 # default function: camera roll
float32 aux5 # default function: payload drop

uint8 mode_switch # main mode 3 position switch (mandatory): _MANUAL_, ASSIST, AUTO
uint8 return_switch # return to launch 2 position switch (mandatory): _NORMAL_, RTL
uint8 rattitude_switch # rattitude control 2 position switch (optional): _MANUAL, RATTITUDE
uint8 posctl_switch # position control 2 position switch (optional): _ALTCTL_, POSCTL
uint8 loiter_switch # loiter 2 position switch (optional): _MISSION_, LOITER
uint8 acro_switch # acro 2 position switch (optional): _MANUAL_, ACRO
uint8 offboard_switch # offboard 2 position switch (optional): _NORMAL_, OFFBOARD
uint8 kill_switch # throttle kill: _NORMAL_, KILL
uint8 arm_switch # arm/disarm switch: _DISARMED_, ARMED
uint8 transition_switch # VTOL transition switch: _HOVER, FORWARD_FLIGHT
uint8 gear_switch # landing gear switch: _DOWN_, UP
int8 mode_slot # the slot a specific model selector is in
uint8 data_source # where this input is coming from
uint8 stab_switch # stabilize switch (only relevant for fixed wings, optional): _MANUAL, STABILIZED
uint8 man_switch # manual switch (only relevant for fixed wings, optional): _STABILIZED_, MANUAL
34 changes: 34 additions & 0 deletions msg/manual_control_switches.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@

uint64 timestamp # time since system start (microseconds)

uint8 SWITCH_POS_NONE = 0 # switch is not mapped
uint8 SWITCH_POS_ON = 1 # switch activated (value = 1)
uint8 SWITCH_POS_MIDDLE = 2 # middle position (value = 0)
uint8 SWITCH_POS_OFF = 3 # switch not activated (value = -1)

int8 MODE_SLOT_NONE = -1 # no mode slot assigned
int8 MODE_SLOT_1 = 0 # mode slot 1 selected
int8 MODE_SLOT_2 = 1 # mode slot 2 selected
int8 MODE_SLOT_3 = 2 # mode slot 3 selected
int8 MODE_SLOT_4 = 3 # mode slot 4 selected
int8 MODE_SLOT_5 = 4 # mode slot 5 selected
int8 MODE_SLOT_6 = 5 # mode slot 6 selected
int8 MODE_SLOT_MAX = 6 # number of slots

uint64 timestamp_last_signal # last valid reception time

int8 mode_slot # the slot a specific model selector is in

uint8 mode_switch # main mode 3 position switch (mandatory): _MANUAL_, ASSIST, AUTO
uint8 return_switch # return to launch 2 position switch (mandatory): _NORMAL_, RTL
uint8 rattitude_switch # rattitude control 2 position switch (optional): _MANUAL, RATTITUDE
uint8 posctl_switch # position control 2 position switch (optional): _ALTCTL_, POSCTL
uint8 loiter_switch # loiter 2 position switch (optional): _MISSION_, LOITER
uint8 acro_switch # acro 2 position switch (optional): _MANUAL_, ACRO
uint8 offboard_switch # offboard 2 position switch (optional): _NORMAL_, OFFBOARD
uint8 kill_switch # throttle kill: _NORMAL_, KILL
uint8 arm_switch # arm/disarm switch: _DISARMED_, ARMED
uint8 transition_switch # VTOL transition switch: _HOVER, FORWARD_FLIGHT
uint8 gear_switch # landing gear switch: _DOWN_, UP
uint8 stab_switch # stabilize switch (only relevant for fixed wings, optional): _MANUAL, STABILIZED
uint8 man_switch # manual switch (only relevant for fixed wings, optional): _STABILIZED_, MANUAL
29 changes: 18 additions & 11 deletions src/lib/FlightTasks/tasks/Manual/FlightTaskManual.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,10 @@ bool FlightTaskManual::initializeSubscriptions(SubscriptionArray &subscription_a
return false;
}

if (!subscription_array.get(ORB_ID(manual_control_switches), _sub_manual_control_switches)) {
return false;
}

return true;
}

Expand Down Expand Up @@ -86,18 +90,21 @@ bool FlightTaskManual::_evaluateSticks()
_sticks_expo(2) = math::expo_deadzone(_sticks(2), _z_vel_man_expo.get(), _stick_dz.get());
_sticks_expo(3) = math::expo_deadzone(_sticks(3), _yaw_expo.get(), _stick_dz.get());

// Only switch the landing gear up if the user switched from gear down to gear up.
// If the user had the switch in the gear up position and took off ignore it
// until he toggles the switch to avoid retracting the gear immediately on takeoff.
int8_t gear_switch = _sub_manual_control_setpoint->get().gear_switch;
// landing gear
if ((_time_stamp_current - _sub_manual_control_switches->get().timestamp) < rc_timeout) {
// Only switch the landing gear up if the user switched from gear down to gear up.
// If the user had the switch in the gear up position and took off ignore it
// until he toggles the switch to avoid retracting the gear immediately on takeoff.
int8_t gear_switch = _sub_manual_control_switches->get().gear_switch;

if (!_constraints.landing_gear) {
if (gear_switch == manual_control_setpoint_s::SWITCH_POS_OFF) {
if (!_constraints.landing_gear) {
if (gear_switch == manual_control_switches_s::SWITCH_POS_OFF) {
_applyGearSwitch(gear_switch);
}

} else {
_applyGearSwitch(gear_switch);
}

} else {
_applyGearSwitch(gear_switch);
}

// valid stick inputs are required
Expand All @@ -119,11 +126,11 @@ bool FlightTaskManual::_evaluateSticks()

void FlightTaskManual::_applyGearSwitch(uint8_t gswitch)
{
if (gswitch == manual_control_setpoint_s::SWITCH_POS_OFF) {
if (gswitch == manual_control_switches_s::SWITCH_POS_OFF) {
_constraints.landing_gear = vehicle_constraints_s::GEAR_DOWN;
}

if (gswitch == manual_control_setpoint_s::SWITCH_POS_ON) {
if (gswitch == manual_control_switches_s::SWITCH_POS_ON) {
_constraints.landing_gear = vehicle_constraints_s::GEAR_UP;
}
}
2 changes: 2 additions & 0 deletions src/lib/FlightTasks/tasks/Manual/FlightTaskManual.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@

#include "FlightTask.hpp"
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/manual_control_switches.h>

class FlightTaskManual : public FlightTask
{
Expand All @@ -68,6 +69,7 @@ class FlightTaskManual : public FlightTask
void _applyGearSwitch(uint8_t gswitch); /**< Sets gears according to switch */

uORB::Subscription<manual_control_setpoint_s> *_sub_manual_control_setpoint{nullptr};
uORB::Subscription<manual_control_switches_s> *_sub_manual_control_switches{nullptr};

DEFINE_PARAMETERS_CUSTOM_PARENT(FlightTask,
(ParamFloat<px4::params::MPC_HOLD_DZ>) _stick_dz, /**< 0-deadzone around the center for the sticks */
Expand Down
Loading

0 comments on commit a233853

Please sign in to comment.