forked from Archive/PX4-Autopilot
delete SYS_CTRL_ALLOC
This commit is contained in:
parent
13f9eabd70
commit
15fece7e14
|
@ -482,7 +482,6 @@ if mixers is None:
|
|||
|
||||
actuators = {
|
||||
'version': 1,
|
||||
'show-ui-if': 'SYS_CTRL_ALLOC==1',
|
||||
'outputs_v1': outputs,
|
||||
'functions_v1': functions,
|
||||
'mixer_v1': mixers,
|
||||
|
|
|
@ -216,20 +216,6 @@ def get_actuator_output_params(yaml_config, output_functions,
|
|||
all_params.update(timer_params)
|
||||
output_groups.extend(timer_output_groups)
|
||||
|
||||
# In case of a board w/o IO and >8 PWM channels, pwm_out splits
|
||||
# into 2 instances (if SYS_CTRL_ALLOC==0) and we need to add the
|
||||
# PWM_AUX min/max/disarmed params as well.
|
||||
num_channels = len(timer_groups['types'])
|
||||
if not board_with_io and num_channels > 8:
|
||||
output_groups.append(
|
||||
{
|
||||
'param_prefix': 'PWM_AUX',
|
||||
'channel_label': 'PWM AUX',
|
||||
'instance_start': 1,
|
||||
'num_channels': num_channels - 8,
|
||||
'standard_params': deepcopy(timer_output_groups[0]['standard_params'])
|
||||
})
|
||||
|
||||
else:
|
||||
raise Exception('unknown generator {:}'.format(group['generator']))
|
||||
continue
|
||||
|
|
|
@ -12,8 +12,5 @@ param set-default BAT2_A_PER_V 24
|
|||
# Enable IMU thermal control
|
||||
param set-default SENS_EN_THERMAL 1
|
||||
|
||||
# Set Camera trigger pins to 13/14
|
||||
param set-default TRIG_PINS_EX 12288
|
||||
|
||||
rgbled_pwm start
|
||||
safety_button start
|
||||
|
|
|
@ -14,9 +14,5 @@ param set-default SENS_EN_THERMAL 1
|
|||
|
||||
param set-default SENS_TEMP_ID 6946850
|
||||
|
||||
# Set Camera trigger pins to 13/14
|
||||
param set-default TRIG_PINS_EX 12288
|
||||
|
||||
|
||||
rgbled_pwm start
|
||||
safety_button start
|
||||
|
|
|
@ -1,7 +1,6 @@
|
|||
uint64 timestamp # time since system start (microseconds)
|
||||
|
||||
# Topic to test individual actuator output functions
|
||||
# Note: this is only used with SYS_CTRL_ALLOC=1
|
||||
|
||||
uint8 ACTION_RELEASE_CONTROL = 0 # exit test mode for the given function
|
||||
uint8 ACTION_DO_CONTROL = 1 # enable actuator test mode
|
||||
|
|
|
@ -71,16 +71,7 @@ CameraCapture::CameraCapture() :
|
|||
_p_camera_capture_edge = param_find("CAM_CAP_EDGE");
|
||||
param_get(_p_camera_capture_edge, &_camera_capture_edge);
|
||||
|
||||
|
||||
// get the capture channel from function configuration params
|
||||
param_t p_ctrl_alloc = param_find("SYS_CTRL_ALLOC");
|
||||
int32_t ctrl_alloc = 0;
|
||||
|
||||
if (p_ctrl_alloc != PARAM_INVALID) {
|
||||
param_get(p_ctrl_alloc, &ctrl_alloc);
|
||||
}
|
||||
|
||||
if (ctrl_alloc == 1) {
|
||||
_capture_channel = -1;
|
||||
|
||||
for (unsigned i = 0; i < 16 && _capture_channel == -1; ++i) {
|
||||
|
@ -95,7 +86,6 @@ CameraCapture::CameraCapture() :
|
|||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
_trigger_pub.advertise();
|
||||
}
|
||||
|
|
|
@ -127,44 +127,6 @@ PARAM_DEFINE_FLOAT(TRIG_ACT_TIME, 40.0f);
|
|||
*/
|
||||
PARAM_DEFINE_INT32(TRIG_MODE, 0);
|
||||
|
||||
/**
|
||||
* Camera trigger pin
|
||||
*
|
||||
* Selects which FMU pin is used (range: AUX1-AUX8 on Pixhawk controllers with an I/O board,
|
||||
* MAIN1-MAIN8 on controllers without an I/O board).
|
||||
*
|
||||
* The PWM interface takes two pins per camera, while relay
|
||||
* triggers on every pin individually. Example: Value 56 would trigger on pins 5 and 6.
|
||||
* For GPIO mode Pin 6 will be triggered followed by 5. With a value of 65 pin 5 will
|
||||
* be triggered followed by 6. Pins may be non contiguous. I.E. 16 or 61.
|
||||
* In GPIO mode the delay pin to pin is < .2 uS.
|
||||
*
|
||||
* @min 1
|
||||
* @max 12345678
|
||||
* @decimal 0
|
||||
* @reboot_required true
|
||||
* @group Camera trigger
|
||||
*/
|
||||
PARAM_DEFINE_INT32(TRIG_PINS, 56);
|
||||
|
||||
/**
|
||||
* Camera trigger pin extended
|
||||
*
|
||||
* This Bit mask selects which FMU pin is used (range: AUX9-AUX32)
|
||||
* If the value is not 0 it takes precedence over TRIG_PINS.
|
||||
*
|
||||
* If bits above 8 are set that value is used as the selector for trigger pins.
|
||||
* greater then 8. 0x00000300 Would be Pins 9,10. If the value is
|
||||
*
|
||||
*
|
||||
* @min 0
|
||||
* @max 2147483647
|
||||
* @decimal 0
|
||||
* @reboot_required true
|
||||
* @group Camera trigger
|
||||
*/
|
||||
PARAM_DEFINE_INT32(TRIG_PINS_EX, 0);
|
||||
|
||||
/**
|
||||
* Camera trigger distance
|
||||
*
|
||||
|
|
|
@ -42,15 +42,6 @@ void CameraInterface::get_pins()
|
|||
_pins[i] = -1;
|
||||
}
|
||||
|
||||
param_t p_ctrl_alloc = param_find("SYS_CTRL_ALLOC");
|
||||
int32_t ctrl_alloc = 0;
|
||||
|
||||
if (p_ctrl_alloc != PARAM_INVALID) {
|
||||
param_get(p_ctrl_alloc, &ctrl_alloc);
|
||||
}
|
||||
|
||||
if (ctrl_alloc == 1) {
|
||||
|
||||
unsigned pin_index = 0;
|
||||
|
||||
for (unsigned i = 0; i < 16 && pin_index < arraySize(_pins); ++i) {
|
||||
|
@ -65,57 +56,4 @@ void CameraInterface::get_pins()
|
|||
}
|
||||
}
|
||||
}
|
||||
|
||||
} else {
|
||||
// Get parameter handle
|
||||
param_t p_pin = param_find("TRIG_PINS");
|
||||
param_t p_pin_ex = param_find("TRIG_PINS_EX");
|
||||
|
||||
if (p_pin == PARAM_INVALID && p_pin_ex == PARAM_INVALID) {
|
||||
PX4_ERR("param TRIG_PINS not found");
|
||||
return;
|
||||
}
|
||||
|
||||
int32_t pin_list = 0;
|
||||
int32_t pin_list_ex = 0;
|
||||
|
||||
if (p_pin_ex != PARAM_INVALID) {
|
||||
param_get(p_pin_ex, &pin_list_ex);
|
||||
}
|
||||
|
||||
if (p_pin != PARAM_INVALID) {
|
||||
param_get(p_pin, &pin_list);
|
||||
}
|
||||
|
||||
if (pin_list_ex == 0) {
|
||||
|
||||
// Convert number to individual channels
|
||||
|
||||
unsigned i = 0;
|
||||
int single_pin;
|
||||
|
||||
while ((single_pin = pin_list % 10)) {
|
||||
|
||||
_pins[i] = single_pin - 1;
|
||||
|
||||
if (_pins[i] < 0) {
|
||||
_pins[i] = -1;
|
||||
}
|
||||
|
||||
pin_list /= 10;
|
||||
i++;
|
||||
}
|
||||
|
||||
} else {
|
||||
unsigned int p = 0;
|
||||
|
||||
for (unsigned int i = 0; i < arraySize(_pins); i++) {
|
||||
int32_t v = (pin_list_ex & (1 << i)) ? i : -1;
|
||||
|
||||
if (v > 0) {
|
||||
_pins[p++] = v;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -63,15 +63,6 @@ bool PPSCapture::init()
|
|||
{
|
||||
bool success = false;
|
||||
|
||||
param_t p_ctrl_alloc = param_find("SYS_CTRL_ALLOC");
|
||||
int32_t ctrl_alloc = 0;
|
||||
|
||||
if (p_ctrl_alloc != PARAM_INVALID) {
|
||||
param_get(p_ctrl_alloc, &ctrl_alloc);
|
||||
}
|
||||
|
||||
if (ctrl_alloc == 1) {
|
||||
|
||||
for (unsigned i = 0; i < 16; ++i) {
|
||||
char param_name[17];
|
||||
snprintf(param_name, sizeof(param_name), "%s_%s%d", PARAM_PREFIX, "FUNC", i + 1);
|
||||
|
@ -84,7 +75,6 @@ bool PPSCapture::init()
|
|||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#if defined(PPS_CAPTURE_CHANNEL)
|
||||
|
||||
|
|
|
@ -277,7 +277,6 @@ private:
|
|||
|
||||
perf_counter_t _control_latency_perf;
|
||||
|
||||
/* SYS_CTRL_ALLOC == 1 */
|
||||
FunctionProviderBase *_function_allocated[MAX_ACTUATORS] {}; ///< unique allocated functions
|
||||
FunctionProviderBase *_functions[MAX_ACTUATORS] {}; ///< currently assigned functions
|
||||
OutputFunction _function_assignment[MAX_ACTUATORS] {};
|
||||
|
@ -296,8 +295,6 @@ private:
|
|||
DEFINE_PARAMETERS(
|
||||
(ParamInt<px4::params::MC_AIRMODE>) _param_mc_airmode, ///< multicopter air-mode
|
||||
(ParamFloat<px4::params::MOT_SLEW_MAX>) _param_mot_slew_max,
|
||||
(ParamFloat<px4::params::THR_MDL_FAC>) _param_thr_mdl_fac, ///< thrust to motor control signal modelling factor
|
||||
(ParamBool<px4::params::SYS_CTRL_ALLOC>) _param_sys_ctrl_alloc
|
||||
|
||||
(ParamFloat<px4::params::THR_MDL_FAC>) _param_thr_mdl_fac ///< thrust to motor control signal modelling factor
|
||||
)
|
||||
};
|
||||
|
|
|
@ -63,9 +63,6 @@ public:
|
|||
void SetUp() override
|
||||
{
|
||||
param_control_autosave(false);
|
||||
|
||||
int32_t v = 1;
|
||||
param_set(param_find("SYS_CTRL_ALLOC"), &v);
|
||||
}
|
||||
|
||||
int update(MixingOutput &mixing_output)
|
||||
|
|
|
@ -280,17 +280,3 @@ PARAM_DEFINE_INT32(SYS_BL_UPDATE, 0);
|
|||
* @group System
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SYS_FAILURE_EN, 0);
|
||||
|
||||
|
||||
/**
|
||||
* Enable Dynamic Control Allocation
|
||||
*
|
||||
* If disabled, the existing mixing implementation is used.
|
||||
* If enabled, dynamic control allocation with runtime configuration of the
|
||||
* mixing and output functions is used.
|
||||
*
|
||||
* @boolean
|
||||
* @reboot_required true
|
||||
* @group System
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SYS_CTRL_ALLOC, 1);
|
||||
|
|
|
@ -208,19 +208,12 @@ void LoggedTopics::add_default_topics()
|
|||
//add_optional_topic("vehicle_optical_flow_vel", 100);
|
||||
add_optional_topic("pps_capture");
|
||||
|
||||
// SYS_CTRL_ALLOC: additional dynamic control allocation logging when enabled
|
||||
int32_t sys_ctrl_alloc = 0;
|
||||
param_get(param_find("SYS_CTRL_ALLOC"), &sys_ctrl_alloc);
|
||||
|
||||
_dynamic_control_allocation = sys_ctrl_alloc >= 1;
|
||||
|
||||
if (_dynamic_control_allocation) {
|
||||
// additional control allocation logging
|
||||
add_topic("actuator_motors", 100);
|
||||
add_topic("actuator_servos", 100);
|
||||
add_topic("vehicle_angular_acceleration", 20);
|
||||
add_topic_multi("vehicle_thrust_setpoint", 20, 1);
|
||||
add_topic_multi("vehicle_torque_setpoint", 20, 2);
|
||||
}
|
||||
|
||||
// SYS_HITL: default ground truth logging for simulation
|
||||
int32_t sys_hitl = 0;
|
||||
|
@ -294,15 +287,9 @@ void LoggedTopics::add_high_rate_topics()
|
|||
add_topic("vehicle_attitude_setpoint");
|
||||
add_topic("vehicle_rates_setpoint");
|
||||
|
||||
if (_dynamic_control_allocation) {
|
||||
add_topic("actuator_motors");
|
||||
add_topic("vehicle_thrust_setpoint");
|
||||
add_topic("vehicle_torque_setpoint");
|
||||
|
||||
} else {
|
||||
add_topic("actuator_controls_0");
|
||||
add_topic("actuator_outputs");
|
||||
}
|
||||
}
|
||||
|
||||
void LoggedTopics::add_debug_topics()
|
||||
|
|
|
@ -185,8 +185,6 @@ private:
|
|||
RequestedSubscriptionArray _subscriptions;
|
||||
int _num_mission_subs{0};
|
||||
float _rate_factor{1.0f};
|
||||
|
||||
bool _dynamic_control_allocation{false};
|
||||
};
|
||||
|
||||
} //namespace logger
|
||||
|
|
|
@ -82,9 +82,7 @@ void Sih::run()
|
|||
_vehicle = (VehicleType)constrain(_sih_vtype.get(), static_cast<typeof _sih_vtype.get()>(0),
|
||||
static_cast<typeof _sih_vtype.get()>(2));
|
||||
|
||||
if (_sys_ctrl_alloc.get()) {
|
||||
_actuator_out_sub = uORB::Subscription{ORB_ID(actuator_outputs_sim)};
|
||||
}
|
||||
|
||||
#if defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
lockstep_loop();
|
||||
|
@ -369,12 +367,9 @@ void Sih::read_motors()
|
|||
{
|
||||
actuator_outputs_s actuators_out;
|
||||
|
||||
float pwm_middle = 0.5f * (PWM_DEFAULT_MIN + PWM_DEFAULT_MAX);
|
||||
|
||||
if (_actuator_out_sub.update(&actuators_out)) {
|
||||
_last_actuator_output_time = actuators_out.timestamp;
|
||||
|
||||
if (_sys_ctrl_alloc.get()) {
|
||||
for (int i = 0; i < NB_MOTORS; i++) { // saturate the motor signals
|
||||
if ((_vehicle == VehicleType::FW && i < 3) || (_vehicle == VehicleType::TS && i > 3)) {
|
||||
_u[i] = actuators_out.output[i];
|
||||
|
@ -384,19 +379,6 @@ void Sih::read_motors()
|
|||
_u[i] = _u[i] + _dt / _T_TAU * (u_sp - _u[i]); // first order transfer function with time constant tau
|
||||
}
|
||||
}
|
||||
|
||||
} else {
|
||||
for (int i = 0; i < NB_MOTORS; i++) { // saturate the motor signals
|
||||
if ((_vehicle == VehicleType::FW && i < 3) || (_vehicle == VehicleType::TS
|
||||
&& i > 3)) { // control surfaces in range [-1,1]
|
||||
_u[i] = constrain(2.0f * (actuators_out.output[i] - pwm_middle) / (PWM_DEFAULT_MAX - PWM_DEFAULT_MIN), -1.0f, 1.0f);
|
||||
|
||||
} else { // throttle signals in range [0,1]
|
||||
float u_sp = constrain((actuators_out.output[i] - PWM_DEFAULT_MIN) / (PWM_DEFAULT_MAX - PWM_DEFAULT_MIN), 0.0f, 1.0f);
|
||||
_u[i] = _u[i] + _dt / _T_TAU * (u_sp - _u[i]); // first order transfer function with time constant tau
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -327,7 +327,6 @@ private:
|
|||
(ParamFloat<px4::params::SIH_DISTSNSR_MAX>) _sih_distance_snsr_max,
|
||||
(ParamFloat<px4::params::SIH_DISTSNSR_OVR>) _sih_distance_snsr_override,
|
||||
(ParamFloat<px4::params::SIH_T_TAU>) _sih_thrust_tau,
|
||||
(ParamInt<px4::params::SIH_VEHICLE_TYPE>) _sih_vtype,
|
||||
(ParamBool<px4::params::SYS_CTRL_ALLOC>) _sys_ctrl_alloc
|
||||
(ParamInt<px4::params::SIH_VEHICLE_TYPE>) _sih_vtype
|
||||
)
|
||||
};
|
||||
|
|
|
@ -73,8 +73,6 @@ static void usage(const char *reason)
|
|||
R"DESCR_STR(
|
||||
Utility to test actuators.
|
||||
|
||||
Note: this is only used in combination with SYS_CTRL_ALLOC=1.
|
||||
|
||||
WARNING: remove all props before using this command.
|
||||
)DESCR_STR");
|
||||
|
||||
|
|
Loading…
Reference in New Issue