mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-19 20:49:07 +08:00
Merge branch 'master' of github.com:PX4/Firmware into master2
This commit is contained in:
commit
47562990a1
@ -1,7 +1,5 @@
|
||||
#!nsh
|
||||
#
|
||||
# UNTESTED UNTESTED!
|
||||
#
|
||||
# Generic 10" Hexa coaxial geometry
|
||||
#
|
||||
# Lorenz Meier <lm@inf.ethz.ch>
|
||||
|
||||
@ -194,17 +194,12 @@ void frsky_send_frame1(int uart)
|
||||
}
|
||||
|
||||
/**
|
||||
* Formats the decimal latitude/longitude to the required degrees/minutes/seconds.
|
||||
* Formats the decimal latitude/longitude to the required degrees/minutes.
|
||||
*/
|
||||
static float frsky_format_gps(float dec)
|
||||
{
|
||||
float dms_deg = (int) dec;
|
||||
float dec_deg = dec - dms_deg;
|
||||
float dms_min = (int) (dec_deg * 60);
|
||||
float dec_min = (dec_deg * 60) - dms_min;
|
||||
float dms_sec = dec_min * 60;
|
||||
|
||||
return (dms_deg * 100.0f) + dms_min + (dms_sec / 100.0f);
|
||||
float dm_deg = (int) dec;
|
||||
return (dm_deg * 100.0f) + (dec - dm_deg) * 60;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -232,9 +227,9 @@ void frsky_send_frame2(int uart)
|
||||
struct tm *tm_gps = gmtime(&time_gps);
|
||||
|
||||
course = (global_pos.yaw + M_PI_F) / M_PI_F * 180.0f;
|
||||
lat = frsky_format_gps(abs(global_pos.lat));
|
||||
lat = frsky_format_gps(fabsf(global_pos.lat));
|
||||
lat_ns = (global_pos.lat < 0) ? 'S' : 'N';
|
||||
lon = frsky_format_gps(abs(global_pos.lon));
|
||||
lon = frsky_format_gps(fabsf(global_pos.lon));
|
||||
lon_ew = (global_pos.lon < 0) ? 'W' : 'E';
|
||||
speed = sqrtf(global_pos.vel_n * global_pos.vel_n + global_pos.vel_e * global_pos.vel_e)
|
||||
* 25.0f / 46.0f;
|
||||
|
||||
@ -453,6 +453,10 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
|
||||
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
|
||||
/* AUTO */
|
||||
main_res = main_state_transition(status, MAIN_STATE_AUTO);
|
||||
|
||||
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ACRO) {
|
||||
/* ACRO */
|
||||
main_res = main_state_transition(status, MAIN_STATE_ACRO);
|
||||
}
|
||||
|
||||
} else {
|
||||
@ -652,6 +656,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||
main_states_str[1] = "ALTCTL";
|
||||
main_states_str[2] = "POSCTL";
|
||||
main_states_str[3] = "AUTO";
|
||||
main_states_str[4] = "ACRO";
|
||||
|
||||
char *arming_states_str[ARMING_STATE_MAX];
|
||||
arming_states_str[0] = "INIT";
|
||||
@ -1012,7 +1017,26 @@ int commander_thread_main(int argc, char *argv[])
|
||||
}
|
||||
|
||||
/* update condition_local_position_valid and condition_local_altitude_valid */
|
||||
check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.xy_valid && eph_epv_good, &(status.condition_local_position_valid), &status_changed);
|
||||
/* hysteresis for EPH */
|
||||
bool local_eph_good;
|
||||
|
||||
if (status.condition_global_position_valid) {
|
||||
if (local_position.eph > eph_epv_threshold * 2.0f) {
|
||||
local_eph_good = false;
|
||||
|
||||
} else {
|
||||
local_eph_good = true;
|
||||
}
|
||||
|
||||
} else {
|
||||
if (local_position.eph < eph_epv_threshold) {
|
||||
local_eph_good = true;
|
||||
|
||||
} else {
|
||||
local_eph_good = false;
|
||||
}
|
||||
}
|
||||
check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.xy_valid && local_eph_good, &(status.condition_local_position_valid), &status_changed);
|
||||
check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.z_valid, &(status.condition_local_altitude_valid), &status_changed);
|
||||
|
||||
static bool published_condition_landed_fw = false;
|
||||
@ -1187,7 +1211,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||
* do it only for rotary wings */
|
||||
if (status.is_rotary_wing &&
|
||||
(status.arming_state == ARMING_STATE_ARMED || status.arming_state == ARMING_STATE_ARMED_ERROR) &&
|
||||
(status.main_state == MAIN_STATE_MANUAL || status.condition_landed) &&
|
||||
(status.main_state == MAIN_STATE_MANUAL || status.main_state == MAIN_STATE_ACRO || status.condition_landed) &&
|
||||
sp_man.r < -STICK_ON_OFF_LIMIT && sp_man.z < 0.1f) {
|
||||
|
||||
if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
|
||||
@ -1600,7 +1624,12 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin
|
||||
break;
|
||||
|
||||
case SWITCH_POS_OFF: // MANUAL
|
||||
res = main_state_transition(status, MAIN_STATE_MANUAL);
|
||||
if (sp_man->acro_switch == SWITCH_POS_ON) {
|
||||
res = main_state_transition(status, MAIN_STATE_ACRO);
|
||||
|
||||
} else {
|
||||
res = main_state_transition(status, MAIN_STATE_MANUAL);
|
||||
}
|
||||
// TRANSITION_DENIED is not possible here
|
||||
break;
|
||||
|
||||
@ -1712,6 +1741,17 @@ set_control_mode()
|
||||
navigator_enabled = true;
|
||||
break;
|
||||
|
||||
case MAIN_STATE_ACRO:
|
||||
control_mode.flag_control_manual_enabled = true;
|
||||
control_mode.flag_control_auto_enabled = false;
|
||||
control_mode.flag_control_rates_enabled = true;
|
||||
control_mode.flag_control_attitude_enabled = false;
|
||||
control_mode.flag_control_altitude_enabled = false;
|
||||
control_mode.flag_control_climb_rate_enabled = false;
|
||||
control_mode.flag_control_position_enabled = false;
|
||||
control_mode.flag_control_velocity_enabled = false;
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
@ -15,6 +15,7 @@ enum PX4_CUSTOM_MAIN_MODE {
|
||||
PX4_CUSTOM_MAIN_MODE_ALTCTL,
|
||||
PX4_CUSTOM_MAIN_MODE_POSCTL,
|
||||
PX4_CUSTOM_MAIN_MODE_AUTO,
|
||||
PX4_CUSTOM_MAIN_MODE_ACRO,
|
||||
};
|
||||
|
||||
enum PX4_CUSTOM_SUB_MODE_AUTO {
|
||||
|
||||
@ -222,6 +222,10 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
|
||||
ret = TRANSITION_CHANGED;
|
||||
break;
|
||||
|
||||
case MAIN_STATE_ACRO:
|
||||
ret = TRANSITION_CHANGED;
|
||||
break;
|
||||
|
||||
case MAIN_STATE_ALTCTL:
|
||||
|
||||
/* need at minimum altitude estimate */
|
||||
|
||||
@ -136,6 +136,10 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
|
||||
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
|
||||
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
|
||||
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_READY;
|
||||
|
||||
} else if (status->main_state == MAIN_STATE_ACRO) {
|
||||
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
|
||||
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ACRO;
|
||||
}
|
||||
|
||||
} else {
|
||||
|
||||
@ -162,6 +162,9 @@ private:
|
||||
param_t man_roll_max;
|
||||
param_t man_pitch_max;
|
||||
param_t man_yaw_max;
|
||||
param_t acro_roll_max;
|
||||
param_t acro_pitch_max;
|
||||
param_t acro_yaw_max;
|
||||
} _params_handles; /**< handles for interesting parameters */
|
||||
|
||||
struct {
|
||||
@ -175,6 +178,7 @@ private:
|
||||
float man_roll_max;
|
||||
float man_pitch_max;
|
||||
float man_yaw_max;
|
||||
math::Vector<3> acro_rate_max; /**< max attitude rates in acro mode */
|
||||
} _params;
|
||||
|
||||
/**
|
||||
@ -284,6 +288,7 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() :
|
||||
_params.man_roll_max = 0.0f;
|
||||
_params.man_pitch_max = 0.0f;
|
||||
_params.man_yaw_max = 0.0f;
|
||||
_params.acro_rate_max.zero();
|
||||
|
||||
_rates_prev.zero();
|
||||
_rates_sp.zero();
|
||||
@ -310,6 +315,9 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() :
|
||||
_params_handles.man_roll_max = param_find("MC_MAN_R_MAX");
|
||||
_params_handles.man_pitch_max = param_find("MC_MAN_P_MAX");
|
||||
_params_handles.man_yaw_max = param_find("MC_MAN_Y_MAX");
|
||||
_params_handles.acro_roll_max = param_find("MC_ACRO_R_MAX");
|
||||
_params_handles.acro_pitch_max = param_find("MC_ACRO_P_MAX");
|
||||
_params_handles.acro_yaw_max = param_find("MC_ACRO_Y_MAX");
|
||||
|
||||
/* fetch initial parameter values */
|
||||
parameters_update();
|
||||
@ -386,6 +394,14 @@ MulticopterAttitudeControl::parameters_update()
|
||||
_params.man_pitch_max = math::radians(_params.man_pitch_max);
|
||||
_params.man_yaw_max = math::radians(_params.man_yaw_max);
|
||||
|
||||
/* acro control scale */
|
||||
param_get(_params_handles.acro_roll_max, &v);
|
||||
_params.acro_rate_max(0) = math::radians(v);
|
||||
param_get(_params_handles.acro_pitch_max, &v);
|
||||
_params.acro_rate_max(1) = math::radians(v);
|
||||
param_get(_params_handles.acro_yaw_max, &v);
|
||||
_params.acro_rate_max(2) = math::radians(v);
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
@ -782,11 +798,36 @@ MulticopterAttitudeControl::task_main()
|
||||
|
||||
} else {
|
||||
/* attitude controller disabled, poll rates setpoint topic */
|
||||
vehicle_rates_setpoint_poll();
|
||||
_rates_sp(0) = _v_rates_sp.roll;
|
||||
_rates_sp(1) = _v_rates_sp.pitch;
|
||||
_rates_sp(2) = _v_rates_sp.yaw;
|
||||
_thrust_sp = _v_rates_sp.thrust;
|
||||
if (_v_control_mode.flag_control_manual_enabled) {
|
||||
/* manual rates control - ACRO mode */
|
||||
_rates_sp = math::Vector<3>(_manual_control_sp.y, -_manual_control_sp.x, _manual_control_sp.r).emult(_params.acro_rate_max);
|
||||
_thrust_sp = _manual_control_sp.z;
|
||||
|
||||
/* reset yaw setpoint after ACRO */
|
||||
_reset_yaw_sp = true;
|
||||
|
||||
/* publish attitude rates setpoint */
|
||||
_v_rates_sp.roll = _rates_sp(0);
|
||||
_v_rates_sp.pitch = _rates_sp(1);
|
||||
_v_rates_sp.yaw = _rates_sp(2);
|
||||
_v_rates_sp.thrust = _thrust_sp;
|
||||
_v_rates_sp.timestamp = hrt_absolute_time();
|
||||
|
||||
if (_v_rates_sp_pub > 0) {
|
||||
orb_publish(ORB_ID(vehicle_rates_setpoint), _v_rates_sp_pub, &_v_rates_sp);
|
||||
|
||||
} else {
|
||||
_v_rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &_v_rates_sp);
|
||||
}
|
||||
|
||||
} else {
|
||||
/* attitude controller disabled, poll rates setpoint topic */
|
||||
vehicle_rates_setpoint_poll();
|
||||
_rates_sp(0) = _v_rates_sp.roll;
|
||||
_rates_sp(1) = _v_rates_sp.pitch;
|
||||
_rates_sp(2) = _v_rates_sp.yaw;
|
||||
_thrust_sp = _v_rates_sp.thrust;
|
||||
}
|
||||
}
|
||||
|
||||
if (_v_control_mode.flag_control_rates_enabled) {
|
||||
|
||||
@ -215,3 +215,32 @@ PARAM_DEFINE_FLOAT(MC_MAN_P_MAX, 35.0f);
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_MAN_Y_MAX, 120.0f);
|
||||
|
||||
/**
|
||||
* Max acro roll rate
|
||||
*
|
||||
* @unit deg/s
|
||||
* @min 0.0
|
||||
* @max 360.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_ACRO_R_MAX, 90.0f);
|
||||
|
||||
/**
|
||||
* Max acro pitch rate
|
||||
*
|
||||
* @unit deg/s
|
||||
* @min 0.0
|
||||
* @max 360.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_ACRO_P_MAX, 90.0f);
|
||||
|
||||
/**
|
||||
* Max acro yaw rate
|
||||
*
|
||||
* @unit deg/s
|
||||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_ACRO_Y_MAX, 120.0f);
|
||||
|
||||
@ -199,6 +199,9 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
||||
float y_est[3] = { 0.0f, 0.0f, 0.0f };
|
||||
float z_est[3] = { 0.0f, 0.0f, 0.0f };
|
||||
|
||||
float eph = 1.0;
|
||||
float epv = 1.0;
|
||||
|
||||
float x_est_prev[3], y_est_prev[3], z_est_prev[3];
|
||||
memset(x_est_prev, 0, sizeof(x_est_prev));
|
||||
memset(y_est_prev, 0, sizeof(y_est_prev));
|
||||
@ -535,6 +538,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
||||
|
||||
flow_valid = true;
|
||||
|
||||
eph = fminf(eph, 0.1 / att.R[2][2] / flow_q * fmaxf(1.0f, flow_dist)); // under ideal conditions, on 1m distance assume EPH = 10cm
|
||||
|
||||
} else {
|
||||
w_flow = 0.0f;
|
||||
flow_valid = false;
|
||||
@ -673,6 +678,9 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
||||
corr_gps[2][1] = 0.0f;
|
||||
}
|
||||
|
||||
eph = fminf(eph, gps.eph_m);
|
||||
epv = fminf(epv, gps.epv_m);
|
||||
|
||||
w_gps_xy = min_eph_epv / fmaxf(min_eph_epv, gps.eph_m);
|
||||
w_gps_z = min_eph_epv / fmaxf(min_eph_epv, gps.epv_m);
|
||||
}
|
||||
@ -712,6 +720,10 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
||||
dt = fmaxf(fminf(0.02, dt), 0.002); // constrain dt from 2 to 20 ms
|
||||
t_prev = t;
|
||||
|
||||
/* increase EPH/EPV on each step */
|
||||
eph *= 1.0 + dt;
|
||||
epv += 0.005 * dt; // add 1m to EPV each 200s (baro drift)
|
||||
|
||||
/* use GPS if it's valid and reference position initialized */
|
||||
bool use_gps_xy = ref_inited && gps_valid && params.w_xy_gps_p > MIN_VALID_W;
|
||||
bool use_gps_z = ref_inited && gps_valid && params.w_z_gps_p > MIN_VALID_W;
|
||||
@ -723,7 +735,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
||||
xy_src_time = t;
|
||||
}
|
||||
|
||||
bool can_estimate_xy = (t < xy_src_time + xy_src_timeout);
|
||||
bool can_estimate_xy = eph < max_eph_epv * 1.5;
|
||||
|
||||
bool dist_bottom_valid = (t < sonar_valid_time + sonar_valid_timeout);
|
||||
|
||||
@ -922,6 +934,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
||||
local_pos.landed = landed;
|
||||
local_pos.yaw = att.yaw;
|
||||
local_pos.dist_bottom_valid = dist_bottom_valid;
|
||||
local_pos.eph = eph;
|
||||
local_pos.epv = epv;
|
||||
|
||||
if (local_pos.dist_bottom_valid) {
|
||||
local_pos.dist_bottom = -z_est[0] - surface_offset;
|
||||
@ -950,9 +964,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
||||
|
||||
global_pos.yaw = local_pos.yaw;
|
||||
|
||||
// TODO implement dead-reckoning
|
||||
global_pos.eph = gps.eph_m;
|
||||
global_pos.epv = gps.epv_m;
|
||||
global_pos.eph = eph;
|
||||
global_pos.epv = epv;
|
||||
|
||||
if (vehicle_global_position_pub < 0) {
|
||||
vehicle_global_position_pub = orb_advertise(ORB_ID(vehicle_global_position), &global_pos);
|
||||
|
||||
@ -1119,10 +1119,16 @@ int sdlog2_thread_main(int argc, char *argv[])
|
||||
log_msg.body.log_LPOS.ref_lat = buf.local_pos.ref_lat * 1e7;
|
||||
log_msg.body.log_LPOS.ref_lon = buf.local_pos.ref_lon * 1e7;
|
||||
log_msg.body.log_LPOS.ref_alt = buf.local_pos.ref_alt;
|
||||
log_msg.body.log_LPOS.xy_flags = (buf.local_pos.xy_valid ? 1 : 0) | (buf.local_pos.v_xy_valid ? 2 : 0) | (buf.local_pos.xy_global ? 8 : 0);
|
||||
log_msg.body.log_LPOS.z_flags = (buf.local_pos.z_valid ? 1 : 0) | (buf.local_pos.v_z_valid ? 2 : 0) | (buf.local_pos.z_global ? 8 : 0);
|
||||
log_msg.body.log_LPOS.pos_flags = (buf.local_pos.xy_valid ? 1 : 0) |
|
||||
(buf.local_pos.z_valid ? 2 : 0) |
|
||||
(buf.local_pos.v_xy_valid ? 4 : 0) |
|
||||
(buf.local_pos.v_z_valid ? 8 : 0) |
|
||||
(buf.local_pos.xy_global ? 16 : 0) |
|
||||
(buf.local_pos.z_global ? 32 : 0);
|
||||
log_msg.body.log_LPOS.landed = buf.local_pos.landed;
|
||||
log_msg.body.log_LPOS.ground_dist_flags = (buf.local_pos.dist_bottom_valid ? 1 : 0);
|
||||
log_msg.body.log_LPOS.eph = buf.local_pos.eph;
|
||||
log_msg.body.log_LPOS.epv = buf.local_pos.epv;
|
||||
LOGBUFFER_WRITE_AND_COUNT(LPOS);
|
||||
}
|
||||
|
||||
|
||||
@ -109,10 +109,11 @@ struct log_LPOS_s {
|
||||
int32_t ref_lat;
|
||||
int32_t ref_lon;
|
||||
float ref_alt;
|
||||
uint8_t xy_flags;
|
||||
uint8_t z_flags;
|
||||
uint8_t pos_flags;
|
||||
uint8_t landed;
|
||||
uint8_t ground_dist_flags;
|
||||
float eph;
|
||||
float epv;
|
||||
};
|
||||
|
||||
/* --- LPSP - LOCAL POSITION SETPOINT --- */
|
||||
@ -360,7 +361,7 @@ static const struct log_format_s log_formats[] = {
|
||||
LOG_FORMAT(ATSP, "ffff", "RollSP,PitchSP,YawSP,ThrustSP"),
|
||||
LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
|
||||
LOG_FORMAT(SENS, "fffff", "BaroPres,BaroAlt,BaroTemp,DiffPres,DiffPresFilt"),
|
||||
LOG_FORMAT(LPOS, "ffffffffLLfBBBB", "X,Y,Z,dist,distR,VX,VY,VZ,RLat,RLon,RAlt,XYFlg,ZFlg,LFlg,GFlg"),
|
||||
LOG_FORMAT(LPOS, "ffffffffLLfBBBff", "X,Y,Z,Dist,DistR,VX,VY,VZ,RLat,RLon,RAlt,PFlg,LFlg,GFlg,EPH,EPV"),
|
||||
LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"),
|
||||
LOG_FORMAT(GPS, "QBffLLfffff", "GPSTime,FixType,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog"),
|
||||
LOG_FORMAT(ATTC, "ffff", "Roll,Pitch,Yaw,Thrust"),
|
||||
|
||||
@ -625,6 +625,15 @@ PARAM_DEFINE_INT32(RC_MAP_POSCTL_SW, 0);
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_MAP_LOITER_SW, 0);
|
||||
|
||||
/**
|
||||
* Acro switch channel mapping.
|
||||
*
|
||||
* @min 0
|
||||
* @max 18
|
||||
* @group Radio Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_MAP_ACRO_SW, 0);
|
||||
|
||||
/**
|
||||
* Flaps channel mapping.
|
||||
*
|
||||
@ -756,3 +765,19 @@ PARAM_DEFINE_FLOAT(RC_RETURN_TH, 0.5f);
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RC_LOITER_TH, 0.5f);
|
||||
|
||||
/**
|
||||
* Threshold for selecting acro mode
|
||||
*
|
||||
* min:-1
|
||||
* max:+1
|
||||
*
|
||||
* 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
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RC_ACRO_TH, 0.5f);
|
||||
|
||||
@ -263,6 +263,7 @@ private:
|
||||
int rc_map_return_sw;
|
||||
int rc_map_posctl_sw;
|
||||
int rc_map_loiter_sw;
|
||||
int rc_map_acro_sw;
|
||||
|
||||
int rc_map_flaps;
|
||||
|
||||
@ -278,11 +279,13 @@ private:
|
||||
float rc_posctl_th;
|
||||
float rc_return_th;
|
||||
float rc_loiter_th;
|
||||
float rc_acro_th;
|
||||
bool rc_assist_inv;
|
||||
bool rc_auto_inv;
|
||||
bool rc_posctl_inv;
|
||||
bool rc_return_inv;
|
||||
bool rc_loiter_inv;
|
||||
bool rc_acro_inv;
|
||||
|
||||
float battery_voltage_scaling;
|
||||
float battery_current_scaling;
|
||||
@ -315,6 +318,7 @@ private:
|
||||
param_t rc_map_return_sw;
|
||||
param_t rc_map_posctl_sw;
|
||||
param_t rc_map_loiter_sw;
|
||||
param_t rc_map_acro_sw;
|
||||
|
||||
param_t rc_map_flaps;
|
||||
|
||||
@ -330,6 +334,7 @@ private:
|
||||
param_t rc_posctl_th;
|
||||
param_t rc_return_th;
|
||||
param_t rc_loiter_th;
|
||||
param_t rc_acro_th;
|
||||
|
||||
param_t battery_voltage_scaling;
|
||||
param_t battery_current_scaling;
|
||||
@ -530,6 +535,7 @@ Sensors::Sensors() :
|
||||
/* optional mode switches, not mapped per default */
|
||||
_parameter_handles.rc_map_posctl_sw = param_find("RC_MAP_POSCTL_SW");
|
||||
_parameter_handles.rc_map_loiter_sw = param_find("RC_MAP_LOITER_SW");
|
||||
_parameter_handles.rc_map_acro_sw = param_find("RC_MAP_ACRO_SW");
|
||||
|
||||
_parameter_handles.rc_map_aux1 = param_find("RC_MAP_AUX1");
|
||||
_parameter_handles.rc_map_aux2 = param_find("RC_MAP_AUX2");
|
||||
@ -544,6 +550,7 @@ Sensors::Sensors() :
|
||||
_parameter_handles.rc_posctl_th = param_find("RC_POSCTL_TH");
|
||||
_parameter_handles.rc_return_th = param_find("RC_RETURN_TH");
|
||||
_parameter_handles.rc_loiter_th = param_find("RC_LOITER_TH");
|
||||
_parameter_handles.rc_acro_th = param_find("RC_ACRO_TH");
|
||||
|
||||
/* gyro offsets */
|
||||
_parameter_handles.gyro_offset[0] = param_find("SENS_GYRO_XOFF");
|
||||
@ -687,6 +694,10 @@ Sensors::parameters_update()
|
||||
warnx("%s", paramerr);
|
||||
}
|
||||
|
||||
if (param_get(_parameter_handles.rc_map_acro_sw, &(_parameters.rc_map_acro_sw)) != OK) {
|
||||
warnx("%s", paramerr);
|
||||
}
|
||||
|
||||
if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) {
|
||||
warnx("%s", paramerr);
|
||||
}
|
||||
@ -712,6 +723,9 @@ Sensors::parameters_update()
|
||||
param_get(_parameter_handles.rc_loiter_th, &(_parameters.rc_loiter_th));
|
||||
_parameters.rc_loiter_inv = (_parameters.rc_loiter_th < 0);
|
||||
_parameters.rc_loiter_th = fabs(_parameters.rc_loiter_th);
|
||||
param_get(_parameter_handles.rc_acro_th, &(_parameters.rc_acro_th));
|
||||
_parameters.rc_acro_inv = (_parameters.rc_acro_th < 0);
|
||||
_parameters.rc_acro_th = fabs(_parameters.rc_acro_th);
|
||||
|
||||
/* update RC function mappings */
|
||||
_rc.function[THROTTLE] = _parameters.rc_map_throttle - 1;
|
||||
@ -723,6 +737,7 @@ Sensors::parameters_update()
|
||||
_rc.function[RETURN] = _parameters.rc_map_return_sw - 1;
|
||||
_rc.function[POSCTL] = _parameters.rc_map_posctl_sw - 1;
|
||||
_rc.function[LOITER] = _parameters.rc_map_loiter_sw - 1;
|
||||
_rc.function[ACRO] = _parameters.rc_map_acro_sw - 1;
|
||||
|
||||
_rc.function[FLAPS] = _parameters.rc_map_flaps - 1;
|
||||
|
||||
@ -1508,6 +1523,7 @@ Sensors::rc_poll()
|
||||
manual.posctl_switch = get_rc_sw2pos_position(POSCTL, _parameters.rc_posctl_th, _parameters.rc_posctl_inv);
|
||||
manual.return_switch = get_rc_sw2pos_position(RETURN, _parameters.rc_return_th, _parameters.rc_return_inv);
|
||||
manual.loiter_switch = get_rc_sw2pos_position(LOITER, _parameters.rc_loiter_th, _parameters.rc_loiter_inv);
|
||||
manual.acro_switch = get_rc_sw2pos_position(ACRO, _parameters.rc_acro_th, _parameters.rc_acro_inv);
|
||||
|
||||
/* publish manual_control_setpoint topic */
|
||||
if (_manual_control_pub > 0) {
|
||||
|
||||
@ -447,6 +447,7 @@ public:
|
||||
QUAD_WIDE, /**< quad in wide configuration */
|
||||
HEX_X, /**< hex in X configuration */
|
||||
HEX_PLUS, /**< hex in + configuration */
|
||||
HEX_COX,
|
||||
OCTA_X,
|
||||
OCTA_PLUS,
|
||||
OCTA_COX,
|
||||
|
||||
@ -115,6 +115,14 @@ const MultirotorMixer::Rotor _config_hex_plus[] = {
|
||||
{ 0.866025, 0.500000, 1.00 },
|
||||
{ -0.866025, -0.500000, -1.00 },
|
||||
};
|
||||
const MultirotorMixer::Rotor _config_hex_cox[] = {
|
||||
{ -0.866025, 0.500000, -1.00 },
|
||||
{ -0.866025, 0.500000, 1.00 },
|
||||
{ -0.000000, -1.000000, -1.00 },
|
||||
{ -0.000000, -1.000000, 1.00 },
|
||||
{ 0.866025, 0.500000, -1.00 },
|
||||
{ 0.866025, 0.500000, 1.00 },
|
||||
};
|
||||
const MultirotorMixer::Rotor _config_octa_x[] = {
|
||||
{ -0.382683, 0.923880, -1.00 },
|
||||
{ 0.382683, -0.923880, -1.00 },
|
||||
@ -152,6 +160,7 @@ const MultirotorMixer::Rotor *_config_index[MultirotorMixer::MAX_GEOMETRY] = {
|
||||
&_config_quad_wide[0],
|
||||
&_config_hex_x[0],
|
||||
&_config_hex_plus[0],
|
||||
&_config_hex_cox[0],
|
||||
&_config_octa_x[0],
|
||||
&_config_octa_plus[0],
|
||||
&_config_octa_cox[0],
|
||||
@ -163,6 +172,7 @@ const unsigned _config_rotor_count[MultirotorMixer::MAX_GEOMETRY] = {
|
||||
4, /* quad_wide */
|
||||
6, /* hex_x */
|
||||
6, /* hex_plus */
|
||||
6, /* hex_cox */
|
||||
8, /* octa_x */
|
||||
8, /* octa_plus */
|
||||
8, /* octa_cox */
|
||||
@ -252,6 +262,9 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
|
||||
} else if (!strcmp(geomname, "6x")) {
|
||||
geometry = MultirotorMixer::HEX_X;
|
||||
|
||||
} else if (!strcmp(geomname, "6c")) {
|
||||
geometry = MultirotorMixer::HEX_COX;
|
||||
|
||||
} else if (!strcmp(geomname, "8+")) {
|
||||
geometry = MultirotorMixer::OCTA_PLUS;
|
||||
|
||||
|
||||
@ -52,6 +52,15 @@ set hex_plus {
|
||||
120 CW
|
||||
}
|
||||
|
||||
set hex_cox {
|
||||
60 CW
|
||||
60 CCW
|
||||
180 CW
|
||||
180 CCW
|
||||
-60 CW
|
||||
-60 CCW
|
||||
}
|
||||
|
||||
set octa_x {
|
||||
22.5 CW
|
||||
-157.5 CW
|
||||
@ -85,7 +94,7 @@ set octa_cox {
|
||||
-135 CW
|
||||
}
|
||||
|
||||
set tables {quad_x quad_plus quad_v quad_wide hex_x hex_plus octa_x octa_plus octa_cox}
|
||||
set tables {quad_x quad_plus quad_v quad_wide hex_x hex_plus hex_cox octa_x octa_plus octa_cox}
|
||||
|
||||
proc factors {a d} { puts [format "\t{ %9.6f, %9.6f, %5.2f }," [rcos [expr $a + 90]] [rcos $a] [expr -$d]]}
|
||||
|
||||
@ -104,13 +113,13 @@ foreach table $tables {
|
||||
puts "};"
|
||||
}
|
||||
|
||||
puts "const MultirotorMixer::Rotor *_config_index\[MultirotorMixer::Geometry::MAX_GEOMETRY\] = {"
|
||||
puts "const MultirotorMixer::Rotor *_config_index\[MultirotorMixer::MAX_GEOMETRY\] = {"
|
||||
foreach table $tables {
|
||||
puts [format "\t&_config_%s\[0\]," $table]
|
||||
}
|
||||
puts "};"
|
||||
|
||||
puts "const unsigned _config_rotor_count\[MultirotorMixer::Geometry::MAX_GEOMETRY\] = {"
|
||||
puts "const unsigned _config_rotor_count\[MultirotorMixer::MAX_GEOMETRY\] = {"
|
||||
foreach table $tables {
|
||||
upvar #0 $table angles
|
||||
puts [format "\t%u, /* %s */" [expr [llength $angles] / 2] $table]
|
||||
|
||||
@ -97,6 +97,7 @@ struct manual_control_setpoint_s {
|
||||
switch_pos_t return_switch; /**< return to launch 2 position switch (mandatory): _NORMAL_, RTL */
|
||||
switch_pos_t posctl_switch; /**< position control 2 position switch (optional): _ALTCTL_, POSCTL */
|
||||
switch_pos_t loiter_switch; /**< loiter 2 position switch (optional): _MISSION_, LOITER */
|
||||
switch_pos_t acro_switch; /**< acro 2 position switch (optional): _MANUAL_, ACRO */
|
||||
}; /**< manual control inputs */
|
||||
|
||||
/**
|
||||
|
||||
@ -45,12 +45,12 @@
|
||||
/**
|
||||
* The number of RC channel inputs supported.
|
||||
* Current (Q4/2013) radios support up to 18 channels,
|
||||
* leaving at a sane value of 15.
|
||||
* leaving at a sane value of 16.
|
||||
* This number can be greater then number of RC channels,
|
||||
* because single RC channel can be mapped to multiple
|
||||
* functions, e.g. for various mode switches.
|
||||
*/
|
||||
#define RC_CHANNELS_MAPPED_MAX 15
|
||||
#define RC_CHANNELS_MAPPED_MAX 16
|
||||
|
||||
/**
|
||||
* This defines the mapping of the RC functions.
|
||||
@ -67,12 +67,13 @@ enum RC_CHANNELS_FUNCTION {
|
||||
POSCTL = 6,
|
||||
LOITER = 7,
|
||||
OFFBOARD_MODE = 8,
|
||||
FLAPS = 9,
|
||||
AUX_1 = 10,
|
||||
AUX_2 = 11,
|
||||
AUX_3 = 12,
|
||||
AUX_4 = 13,
|
||||
AUX_5 = 14,
|
||||
ACRO = 9,
|
||||
FLAPS = 10,
|
||||
AUX_1 = 11,
|
||||
AUX_2 = 12,
|
||||
AUX_3 = 13,
|
||||
AUX_4 = 14,
|
||||
AUX_5 = 15,
|
||||
RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
|
||||
};
|
||||
|
||||
|
||||
@ -83,6 +83,8 @@ struct vehicle_local_position_s {
|
||||
float dist_bottom_rate; /**< Distance to bottom surface (ground) change rate */
|
||||
uint64_t surface_bottom_timestamp; /**< Time when new bottom surface found */
|
||||
bool dist_bottom_valid; /**< true if distance to bottom surface is valid */
|
||||
float eph;
|
||||
float epv;
|
||||
};
|
||||
|
||||
/**
|
||||
|
||||
@ -66,6 +66,7 @@ typedef enum {
|
||||
MAIN_STATE_ALTCTL,
|
||||
MAIN_STATE_POSCTL,
|
||||
MAIN_STATE_AUTO,
|
||||
MAIN_STATE_ACRO,
|
||||
MAIN_STATE_MAX
|
||||
} main_state_t;
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user