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

Switch #2

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
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
1 change: 1 addition & 0 deletions msg/commander_state.msg
Original file line number Diff line number Diff line change
Expand Up @@ -17,5 +17,6 @@ uint8 MAIN_STATE_AUTO_FOLLOW_TARGET = 12
uint8 MAIN_STATE_AUTO_PRECLAND = 13
uint8 MAIN_STATE_ORBIT = 14
uint8 MAIN_STATE_MAX = 15
uint8 MAIN_STATE_TILT = 16

uint8 main_state # main state machine
1 change: 1 addition & 0 deletions msg/manual_control_setpoint.msg
Original file line number Diff line number Diff line change
Expand Up @@ -65,3 +65,4 @@ uint8 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
uint8 tilt_switch # tilt enabled 2 position switch (optional): _MANUAL, TILT
3 changes: 2 additions & 1 deletion msg/rc_channels.msg
Original file line number Diff line number Diff line change
Expand Up @@ -27,11 +27,12 @@ uint8 RC_CHANNELS_FUNCTION_ARMSWITCH=23
uint8 RC_CHANNELS_FUNCTION_STAB=24
uint8 RC_CHANNELS_FUNCTION_AUX_6=25
uint8 RC_CHANNELS_FUNCTION_MAN=26
uint8 RC_CHANNELS_FUNCTION_TILT=27

uint64 timestamp_last_valid # Timestamp of last valid RC signal
float32[18] channels # Scaled to -1..1 (throttle: 0..1)
uint8 channel_count # Number of valid channels
int8[27] function # Functions mapping
int8[28] function # Functions mapping
uint8 rssi # Receive signal strength index
bool signal_lost # Control signal lost, should be checked together with topic timeout
uint32 frame_drop_count # Number of dropped frames
1 change: 1 addition & 0 deletions msg/vehicle_control_mode.msg
Original file line number Diff line number Diff line change
Expand Up @@ -18,3 +18,4 @@ bool flag_control_altitude_enabled # true if altitude is controlled
bool flag_control_climb_rate_enabled # true if climb rate is controlled
bool flag_control_termination_enabled # true if flighttermination is enabled
bool flag_control_fixed_hdg_enabled # true if using a fixed heading for user control
bool flag_control_tilt_enabled # true if the mode tilt rotor is enabled
1 change: 1 addition & 0 deletions msg/vehicle_status.msg
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ uint8 NAVIGATION_STATE_AUTO_FOLLOW_TARGET = 19 # Auto Follow
uint8 NAVIGATION_STATE_AUTO_PRECLAND = 20 # Precision land with landing target
uint8 NAVIGATION_STATE_ORBIT = 21 # Orbit in a circle
uint8 NAVIGATION_STATE_MAX = 22
uint8 NAVIGATION_STATE_TILT= 23 # Tilt rotor mode

uint8 RC_IN_MODE_DEFAULT = 0
uint8 RC_IN_MODE_OFF = 1
Expand Down
4 changes: 4 additions & 0 deletions src/drivers/rc_input/crsf_telemetry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -186,6 +186,10 @@ bool CRSFTelemetry::send_flight_mode()
case vehicle_status_s::NAVIGATION_STATE_RATTITUDE:
flight_mode = "Rattitude";
break;

case vehicle_status_s::NAVIGATION_STATE_TILT:
flight_mode = "Tilt";
break;
}

return crsf_send_telemetry_flight_mode(_uart_fd, flight_mode);
Expand Down
17 changes: 17 additions & 0 deletions src/modules/commander/Commander.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -403,6 +403,9 @@ extern "C" __EXPORT int commander_main(int argc, char *argv[])
send_vehicle_command(vehicle_command_s::VEHICLE_CMD_DO_SET_MODE, 1, PX4_CUSTOM_MAIN_MODE_AUTO,
PX4_CUSTOM_SUB_MODE_AUTO_PRECLAND);

} else if (!strcmp(argv[2], "tilt")) {
send_vehicle_command(vehicle_command_s::VEHICLE_CMD_DO_SET_MODE, 1, PX4_CUSTOM_MAIN_MODE_TILT);

} else {
PX4_ERR("argument %s unsupported.", argv[2]);
}
Expand Down Expand Up @@ -673,6 +676,10 @@ Commander::handle_command(vehicle_status_s *status_local, const vehicle_command_

/* OFFBOARD */
main_ret = main_state_transition(*status_local, commander_state_s::MAIN_STATE_OFFBOARD, status_flags, &_internal_state);

} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_TILT) {
/* MANUAL */
main_ret = main_state_transition(*status_local, commander_state_s::MAIN_STATE_TILT, status_flags, &_internal_state);
}

} else {
Expand Down Expand Up @@ -3196,13 +3203,23 @@ Commander::update_control_mode()
&& !status.is_vtol);

switch (status.nav_state) {

case vehicle_status_s::NAVIGATION_STATE_TILT:
control_mode.flag_control_tilt_enabled = true;
control_mode.flag_control_manual_enabled = true;
control_mode.flag_control_rates_enabled = true;
control_mode.flag_control_attitude_enabled = true;
break;

case vehicle_status_s::NAVIGATION_STATE_MANUAL:
control_mode.flag_control_tilt_enabled = false;
control_mode.flag_control_manual_enabled = true;
control_mode.flag_control_rates_enabled = stabilization_required();
control_mode.flag_control_attitude_enabled = stabilization_required();
break;

case vehicle_status_s::NAVIGATION_STATE_STAB:
control_mode.flag_control_tilt_enabled = true;
control_mode.flag_control_manual_enabled = true;
control_mode.flag_control_rates_enabled = true;
control_mode.flag_control_attitude_enabled = true;
Expand Down
6 changes: 6 additions & 0 deletions src/modules/commander/commander_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -389,6 +389,7 @@ PARAM_DEFINE_INT32(COM_OBL_RC_ACT, 0);
* @value 7 Offboard
* @value 8 Stabilized
* @value 9 Rattitude
* @value 10 Tilt
* @value 12 Follow Me
* @group Commander
*/
Expand All @@ -413,6 +414,7 @@ PARAM_DEFINE_INT32(COM_FLTMODE1, -1);
* @value 7 Offboard
* @value 8 Stabilized
* @value 9 Rattitude
* @value 10 Tilt
* @value 12 Follow Me
* @group Commander
*/
Expand All @@ -437,6 +439,7 @@ PARAM_DEFINE_INT32(COM_FLTMODE2, -1);
* @value 7 Offboard
* @value 8 Stabilized
* @value 9 Rattitude
* @value 10 Tilt
* @value 12 Follow Me
* @group Commander
*/
Expand All @@ -461,6 +464,7 @@ PARAM_DEFINE_INT32(COM_FLTMODE3, -1);
* @value 7 Offboard
* @value 8 Stabilized
* @value 9 Rattitude
* @value 10 Tilt
* @value 12 Follow Me
* @group Commander
*/
Expand All @@ -485,6 +489,7 @@ PARAM_DEFINE_INT32(COM_FLTMODE4, -1);
* @value 7 Offboard
* @value 8 Stabilized
* @value 9 Rattitude
* @value 10 Tilt
* @value 12 Follow Me
* @group Commander
*/
Expand All @@ -509,6 +514,7 @@ PARAM_DEFINE_INT32(COM_FLTMODE5, -1);
* @value 7 Offboard
* @value 8 Stabilized
* @value 9 Rattitude
* @value 10 Tilt
* @value 12 Follow Me
* @group Commander
*/
Expand Down
3 changes: 2 additions & 1 deletion src/modules/commander/px4_custom_mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,8 @@ enum PX4_CUSTOM_MAIN_MODE {
PX4_CUSTOM_MAIN_MODE_OFFBOARD,
PX4_CUSTOM_MAIN_MODE_STABILIZED,
PX4_CUSTOM_MAIN_MODE_RATTITUDE,
PX4_CUSTOM_MAIN_MODE_SIMPLE /* unused, but reserved for future use */
PX4_CUSTOM_MAIN_MODE_SIMPLE, /* unused, but reserved for future use */
PX4_CUSTOM_MAIN_MODE_TILT
};

enum PX4_CUSTOM_SUB_MODE_AUTO {
Expand Down
7 changes: 7 additions & 0 deletions src/modules/commander/state_machine_helper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -266,6 +266,7 @@ main_state_transition(const vehicle_status_s &status, const main_state_t new_mai
case commander_state_s::MAIN_STATE_MANUAL:
case commander_state_s::MAIN_STATE_STAB:
case commander_state_s::MAIN_STATE_ACRO:
case commander_state_s::MAIN_STATE_TILT:
case commander_state_s::MAIN_STATE_RATTITUDE:
ret = TRANSITION_CHANGED;
break;
Expand Down Expand Up @@ -698,6 +699,12 @@ bool set_nav_state(vehicle_status_s *status, actuator_armed_s *armed, commander_
} else {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_OFFBOARD;
}
break;

case commander_state_s::MAIN_STATE_TILT:
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TILT;
break;


default:
break;
Expand Down
1 change: 1 addition & 0 deletions src/modules/fw_att_control/FixedwingAttitudeControl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -182,6 +182,7 @@ class FixedwingAttitudeControl final : public ModuleBase<FixedwingAttitudeContro
(ParamFloat<px4::params::FW_PSP_OFF>) _param_fw_psp_off,

(ParamFloat<px4::params::FW_RATT_TH>) _param_fw_ratt_th,
(ParamFloat<px4::params::FW_TILT_TH>) _param_fw_tilt_th,

(ParamFloat<px4::params::FW_R_RMAX>) _param_fw_r_rmax,
(ParamFloat<px4::params::FW_R_TC>) _param_fw_r_tc,
Expand Down
14 changes: 14 additions & 0 deletions src/modules/fw_att_control/fw_att_control_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -662,6 +662,20 @@ PARAM_DEFINE_FLOAT(FW_ACRO_Z_MAX, 45);
*/
PARAM_DEFINE_FLOAT(FW_RATT_TH, 0.8f);

/**
* Threshold for Tilt mode
*
* Manual input needed in order to override attitude control rate setpoints
* and instead pass manual stick inputs as rate setpoints
*
* @min 0.0
* @max 1.0
* @decimal 2
* @increment 0.01
* @group FW Attitude Control
*/
PARAM_DEFINE_FLOAT(FW_TILT_TH, 0.9f);

/**
* Roll trim increment at minimum airspeed
*
Expand Down
5 changes: 5 additions & 0 deletions src/modules/mc_att_control/mc_att_control.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,8 @@
#include <uORB/topics/vehicle_land_detected.h>
#include <vtol_att_control/vtol_type.h>
#include <lib/ecl/AlphaFilter/AlphaFilter.hpp>
#include <uORB/uORB.h>
#include <uORB/topics/manual_control_setpoint.h>

#include <AttitudeControl.hpp>

Expand Down Expand Up @@ -134,6 +136,9 @@ class MulticopterAttitudeControl : public ModuleBase<MulticopterAttitudeControl>

uint8_t _quat_reset_counter{0};

int vehicle_control_mode_sp_sub_fd = orb_subscribe(ORB_ID(vehicle_control_mode));
struct vehicle_control_mode_s vehicle_control_mode_sp {};

DEFINE_PARAMETERS(
(ParamFloat<px4::params::MC_ROLL_P>) _param_mc_roll_p,
(ParamFloat<px4::params::MC_PITCH_P>) _param_mc_pitch_p,
Expand Down
9 changes: 7 additions & 2 deletions src/modules/mc_att_control/mc_att_control_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,6 @@
*/

#include "mc_att_control.hpp"

#include <drivers/drv_hrt.h>
#include <mathlib/math/Limits.hpp>
#include <mathlib/math/Functions.hpp>
Expand Down Expand Up @@ -162,7 +161,13 @@ MulticopterAttitudeControl::generate_attitude_setpoint(const Quatf &q, float dt,
Quatf q_sp_rpy = AxisAnglef(v(0), v(1), 0.f);
Eulerf euler_sp = q_sp_rpy;
attitude_setpoint.roll_body = euler_sp(0);
attitude_setpoint.pitch_body = math::constrain(euler_sp(1),0.0f,1000.0f);
orb_copy(ORB_ID(vehicle_control_mode), vehicle_control_mode_sp_sub_fd, &vehicle_control_mode_sp);
bool _tilt_enabled=vehicle_control_mode_sp.flag_control_tilt_enabled;
if(_tilt_enabled==true){
attitude_setpoint.pitch_body = math::constrain(euler_sp(1),0.0f,1000.0f);
} else {
attitude_setpoint.pitch_body = euler_sp(1);
}
// The axis angle can change the yaw as well (noticeable at higher tilt angles).
// This is the formula by how much the yaw changes:
// let a := tilt angle, b := atan(y/x) (direction of maximum tilt)
Expand Down
14 changes: 14 additions & 0 deletions src/modules/mc_att_control/mc_att_control_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -164,6 +164,20 @@ PARAM_DEFINE_FLOAT(MC_YAWRATE_MAX, 200.0f);
*/
PARAM_DEFINE_FLOAT(MC_RATT_TH, 0.8f);

/**
* Threshold for Tilt mode
*
* Manual input needed in order to override attitude control rate setpoints
* and instead pass manual stick inputs as rate setpoints
*
* @min 0.0
* @max 1.0
* @decimal 2
* @increment 0.01
* @group Multicopter Attitude Control
*/
PARAM_DEFINE_FLOAT(MC_TILT_TH, 0.9f);

/**
* Manual tilt input filter time constant
* Setting this parameter to 0 disables the filter
Expand Down
44 changes: 44 additions & 0 deletions src/modules/rc_update/params.c
Original file line number Diff line number Diff line change
Expand Up @@ -1726,6 +1726,34 @@ PARAM_DEFINE_INT32(RC_MAP_STAB_SW, 0);
*/
PARAM_DEFINE_INT32(RC_MAP_MAN_SW, 0);

/**
* Tilt switch channel
*
* @min 0
* @max 18
* @group Radio Switches
* @value 0 Unassigned
* @value 1 Channel 1
* @value 2 Channel 2
* @value 3 Channel 3
* @value 4 Channel 4
* @value 5 Channel 5
* @value 6 Channel 6
* @value 7 Channel 7
* @value 8 Channel 8
* @value 9 Channel 9
* @value 10 Channel 10
* @value 11 Channel 11
* @value 12 Channel 12
* @value 13 Channel 13
* @value 14 Channel 14
* @value 15 Channel 15
* @value 16 Channel 16
* @value 17 Channel 17
* @value 18 Channel 18
*/
PARAM_DEFINE_INT32(RC_MAP_TILT_SW, 0);

/**
* AUX1 Passthrough RC channel
*
Expand Down Expand Up @@ -2227,4 +2255,20 @@ PARAM_DEFINE_FLOAT(RC_STAB_TH, 0.5f);
* @max 1
* @group Radio Switches
*/
PARAM_DEFINE_FLOAT(RC_TILT_TH, 0.75f);

/**
* Threshold for selecting Tilt mode
*
* 0-1 indicate where in the full channel range the threshold sits
* 0 : min
* 1 : max
* sign indicates polarity of comparison
* positive : true when channel>th
* negative : true when channel<th
*
* @min -1
* @max 1
* @group Radio Switches
*/
PARAM_DEFINE_FLOAT(RC_MAN_TH, 0.75f);
3 changes: 3 additions & 0 deletions src/modules/rc_update/rc_update.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,6 +160,7 @@ RCUpdate::update_rc_functions()
_rc.function[rc_channels_s::RC_CHANNELS_FUNCTION_STAB] = _param_rc_map_stab_sw.get() - 1;
_rc.function[rc_channels_s::RC_CHANNELS_FUNCTION_MAN] = _param_rc_map_man_sw.get() - 1;

_rc.function[rc_channels_s::RC_CHANNELS_FUNCTION_TILT] = _param_rc_map_tilt_sw.get() - 1;
_rc.function[rc_channels_s::RC_CHANNELS_FUNCTION_FLAPS] = _param_rc_map_flaps.get() - 1;

_rc.function[rc_channels_s::RC_CHANNELS_FUNCTION_AUX_1] = _param_rc_map_aux1.get() - 1;
Expand Down Expand Up @@ -521,6 +522,8 @@ RCUpdate::Run()
_param_rc_stab_th.get(), _param_rc_stab_th.get() < 0.f);
manual_control_setpoint.man_switch = get_rc_sw2pos_position(rc_channels_s::RC_CHANNELS_FUNCTION_MAN,
_param_rc_man_th.get(), _param_rc_man_th.get() < 0.f);
manual_control_setpoint.tilt_switch = get_rc_sw2pos_position(rc_channels_s::RC_CHANNELS_FUNCTION_TILT,
_param_rc_tilt_th.get(), _param_rc_tilt_th.get() < 0.f);

/* publish manual_control_setpoint topic */
_manual_control_setpoint_pub.publish(manual_control_setpoint);
Expand Down
2 changes: 2 additions & 0 deletions src/modules/rc_update/rc_update.h
Original file line number Diff line number Diff line change
Expand Up @@ -195,6 +195,7 @@ class RCUpdate : public ModuleBase<RCUpdate>, public ModuleParams, public px4::W
(ParamInt<px4::params::RC_MAP_GEAR_SW>) _param_rc_map_gear_sw,
(ParamInt<px4::params::RC_MAP_STAB_SW>) _param_rc_map_stab_sw,
(ParamInt<px4::params::RC_MAP_MAN_SW>) _param_rc_map_man_sw,
(ParamInt<px4::params::RC_MAP_TILT_SW>) _param_rc_map_tilt_sw,

(ParamInt<px4::params::RC_MAP_AUX1>) _param_rc_map_aux1,
(ParamInt<px4::params::RC_MAP_AUX2>) _param_rc_map_aux2,
Expand All @@ -219,6 +220,7 @@ class RCUpdate : public ModuleBase<RCUpdate>, public ModuleParams, public px4::W
(ParamFloat<px4::params::RC_STAB_TH>) _param_rc_stab_th,
(ParamFloat<px4::params::RC_MAN_TH>) _param_rc_man_th,
(ParamFloat<px4::params::RC_RETURN_TH>) _param_rc_return_th,
(ParamFloat<px4::params::RC_TILT_TH>) _param_rc_tilt_th,

(ParamInt<px4::params::RC_CHAN_CNT>) _param_rc_chan_cnt
)
Expand Down
10 changes: 8 additions & 2 deletions src/modules/vtol_att_control/tiltrotor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -434,9 +434,15 @@ void Tiltrotor::fill_actuator_outputs()

//AIGHTECH

orb_copy(ORB_ID(manual_control_setpoint), manual_sp_sub_fd, &manual_control_sp);
orb_copy(ORB_ID(manual_control_setpoint), manual_sp_sub_fd, &manual_control_sp);
orb_copy(ORB_ID(vehicle_control_mode), vehicle_control_mode_sp_sub_fd, &vehicle_control_mode_sp);
_tilt_control=manual_control_sp.x;
_actuators_out_0->control[4] = _tilt_control;
bool _tilt_enabled=vehicle_control_mode_sp.flag_control_tilt_enabled;
if(_tilt_enabled==true){
_actuators_out_0->control[4] = _tilt_control;
} else {
_actuators_out_0->control[4] = 0;
}
//PX4_INFO("%d %d %d", actuator_controls_s::INDEX_ROLL, actuator_controls_s::INDEX_PITCH, actuator_controls_s::INDEX_YAW);
if (_params->elevons_mc_lock && _vtol_schedule.flight_mode == vtol_mode::MC_MODE) {
_actuators_out_1->control[actuator_controls_s::INDEX_ROLL] = 0.0f;
Expand Down
3 changes: 3 additions & 0 deletions src/modules/vtol_att_control/tiltrotor.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@
#include <drivers/drv_hrt.h>
#include <uORB/uORB.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/vehicle_control_mode.h>
class Tiltrotor : public VtolType
{

Expand Down Expand Up @@ -106,6 +107,8 @@ class Tiltrotor : public VtolType
bool _tilt_motors_for_startup{false};
//AIGHTECH
int manual_sp_sub_fd = orb_subscribe(ORB_ID(manual_control_setpoint));
int vehicle_control_mode_sp_sub_fd = orb_subscribe(ORB_ID(vehicle_control_mode));
struct vehicle_control_mode_s vehicle_control_mode_sp {};
struct manual_control_setpoint_s manual_control_sp {};

};
Expand Down