Skip to content

Commit

Permalink
fix: format checks
Browse files Browse the repository at this point in the history
  • Loading branch information
Pedro-Roque committed May 13, 2024
1 parent 35700c2 commit 697bcde
Show file tree
Hide file tree
Showing 18 changed files with 498 additions and 448 deletions.
1 change: 1 addition & 0 deletions src/lib/mixer_module/actuator_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,7 @@ void ActuatorTest::update(int num_outputs, float thrust_curve)
value += trim.trim[idx];
}
}

_current_outputs[i] = value;

} else {
Expand Down
5 changes: 3 additions & 2 deletions src/lib/mixer_module/functions/FunctionThrusters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,8 @@ class FunctionThrusters : public FunctionProviderBase
static_assert(actuator_motors_s::NUM_CONTROLS == (int)OutputFunction::ThrusterMax - (int)OutputFunction::Thruster1 + 1,
"Unexpected num thrusters");

static_assert(actuator_motors_s::ACTUATOR_FUNCTION_THRUSTER1 == (int)OutputFunction::Thruster1, "Unexpected thruster idx");
static_assert(actuator_motors_s::ACTUATOR_FUNCTION_THRUSTER1 == (int)OutputFunction::Thruster1,
"Unexpected thruster idx");

FunctionThrusters(const Context &context) :
_topic(&context.work_item, ORB_ID(actuator_motors)),
Expand Down Expand Up @@ -76,7 +77,7 @@ class FunctionThrusters : public FunctionProviderBase
{
// TODO(@Pedro-Roque): for now bypass this
/*if (thrust_factor > 0.f && thrust_factor <= 1.f) {
// thrust factor
// rel_thrust = factor * x^2 + (1-factor) * x,
const float a = thrust_factor;
Expand Down
2 changes: 1 addition & 1 deletion src/lib/mixer_module/mixer_module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -239,7 +239,7 @@ bool MixingOutput::updateSubscriptions(bool allow_wq_switch)

if (_param_handles[i].function != PARAM_INVALID && param_get(_param_handles[i].function, &function) == 0) {
if ((function >= (int32_t)OutputFunction::Motor1 && function <= (int32_t)OutputFunction::MotorMax) ||
(function >= (int32_t)OutputFunction::Thruster1 && function <= (int32_t)OutputFunction::ThrusterMax)) {
(function >= (int32_t)OutputFunction::Thruster1 && function <= (int32_t)OutputFunction::ThrusterMax)) {
switch_requested = true;
}
}
Expand Down
1 change: 1 addition & 0 deletions src/modules/commander/Commander.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1718,6 +1718,7 @@ void Commander::updateParameters()

} else if (is_ground) {
_vehicle_status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_ROVER;

} else if (is_space) {
_vehicle_status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_SPACECRAFT;
}
Expand Down
3 changes: 2 additions & 1 deletion src/modules/commander/ModeUtil/control_mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,8 @@ namespace mode_util

static bool stabilization_required(uint8_t vehicle_type)
{
return vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING || vehicle_type == vehicle_status_s::VEHICLE_TYPE_SPACECRAFT;
return vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING
|| vehicle_type == vehicle_status_s::VEHICLE_TYPE_SPACECRAFT;
}

static bool if_not_spacecraft(uint8_t vehicle_type)
Expand Down
3 changes: 2 additions & 1 deletion src/modules/commander/commander_helper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,8 @@ bool is_ground_vehicle(const vehicle_status_s &current_status)

bool is_spacecraft(const vehicle_status_s &current_status)
{
return (current_status.system_type == VEHICLE_TYPE_SPACECRAFT_2D || current_status.system_type == VEHICLE_TYPE_SPACECRAFT_3D);
return (current_status.system_type == VEHICLE_TYPE_SPACECRAFT_2D
|| current_status.system_type == VEHICLE_TYPE_SPACECRAFT_3D);
}

// End time for currently blinking LED message, 0 if no blink message
Expand Down
2 changes: 1 addition & 1 deletion src/modules/commander/commander_helper.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ bool is_vtol(const vehicle_status_s &current_status);
bool is_vtol_tailsitter(const vehicle_status_s &current_status);
bool is_fixed_wing(const vehicle_status_s &current_status);
bool is_ground_vehicle(const vehicle_status_s &current_status);
bool is_spacecraft(const vehicle_status_s& current_status);
bool is_spacecraft(const vehicle_status_s &current_status);

int buzzer_init(void);
void buzzer_deinit(void);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,5 +61,5 @@ void ActuatorEffectivenessSpacecraft::updateSetpoint(const matrix::Vector<float,
{
// TODO(@E-Krantz): Here is where we can add the nonlinearity of multiple thrusters open
// and how to adjust thrust in that time
return;
return;
}
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ ActuatorEffectivenessThrusters::ActuatorEffectivenessThrusters(ModuleParams *par
bool tilt_support)
: ModuleParams(parent), _axis_config(axis_config), _tilt_support(tilt_support)
{

for (int i = 0; i < NUM_THRUSTERS_MAX; ++i) {
char buffer[17];
snprintf(buffer, sizeof(buffer), "CA_THRUSTER%u_PX", i);
Expand All @@ -58,21 +58,21 @@ ActuatorEffectivenessThrusters::ActuatorEffectivenessThrusters(ModuleParams *par
_param_handles[i].position_z = param_find(buffer);

if (_axis_config == AxisConfiguration::Configurable) {
snprintf(buffer, sizeof(buffer), "CA_THRUSTER%u_AX", i);
_param_handles[i].axis_x = param_find(buffer);
snprintf(buffer, sizeof(buffer), "CA_THRUSTER%u_AY", i);
_param_handles[i].axis_y = param_find(buffer);
snprintf(buffer, sizeof(buffer), "CA_THRUSTER%u_AZ", i);
_param_handles[i].axis_z = param_find(buffer);
snprintf(buffer, sizeof(buffer), "CA_THRUSTER%u_AX", i);
_param_handles[i].axis_x = param_find(buffer);
snprintf(buffer, sizeof(buffer), "CA_THRUSTER%u_AY", i);
_param_handles[i].axis_y = param_find(buffer);
snprintf(buffer, sizeof(buffer), "CA_THRUSTER%u_AZ", i);
_param_handles[i].axis_z = param_find(buffer);
}

snprintf(buffer, sizeof(buffer), "CA_THRUSTER%u_CT", i);
_param_handles[i].thrust_coef = param_find(buffer);

if (_tilt_support) {
PX4_ERR("Tilt support not implemented");
}
}
}

_count_handle = param_find("CA_THRUSTER_CNT");

Expand Down Expand Up @@ -101,12 +101,12 @@ void ActuatorEffectivenessThrusters::updateParams()
Vector3f &axis = _geometry.thrusters[i].axis;

switch (_axis_config) {
case AxisConfiguration::Configurable:
param_get(_param_handles[i].axis_x, &axis(0));
param_get(_param_handles[i].axis_y, &axis(1));
param_get(_param_handles[i].axis_z, &axis(2));
break;
}
case AxisConfiguration::Configurable:
param_get(_param_handles[i].axis_x, &axis(0));
param_get(_param_handles[i].axis_y, &axis(1));
param_get(_param_handles[i].axis_z, &axis(2));
break;
}

param_get(_param_handles[i].thrust_coef, &_geometry.thrusters[i].thrust_coef);
}
Expand All @@ -119,6 +119,7 @@ ActuatorEffectivenessThrusters::addActuators(Configuration &configuration)
PX4_ERR("Wrong actuator ordering: servos need to be after motors");
return false;
}

int num_actuators = computeEffectivenessMatrix(_geometry,
configuration.effectiveness_matrices[configuration.selected_matrix],
configuration.num_actuators_matrix[configuration.selected_matrix]);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,15 +72,16 @@ class ActuatorEffectivenessThrusters : public ModuleParams, public ActuatorEffec
};

ActuatorEffectivenessThrusters(ModuleParams *parent, AxisConfiguration axis_config = AxisConfiguration::Configurable,
bool tilt_support = false);
bool tilt_support = false);
virtual ~ActuatorEffectivenessThrusters() = default;

bool getEffectivenessMatrix(Configuration &configuration, EffectivenessUpdateReason external_update) override;

void getDesiredAllocationMethod(AllocationMethod allocation_method_out[MAX_NUM_MATRICES]) const override
{
allocation_method_out[0] = AllocationMethod::SEQUENTIAL_DESATURATION; // TODO(@Jaeyoung-Lim): needs to be updated based on metric mixer
}
allocation_method_out[0] =
AllocationMethod::SEQUENTIAL_DESATURATION; // TODO(@Jaeyoung-Lim): needs to be updated based on metric mixer
}

void getNormalizeRPY(bool normalize[MAX_NUM_MATRICES]) const override
{
Expand Down
12 changes: 10 additions & 2 deletions src/modules/control_allocator/ControlAllocator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -446,9 +446,11 @@ ControlAllocator::Run()
_actuator_effectiveness->allocateAuxilaryControls(dt, i, _control_allocation[i]->_actuator_sp); //flaps and spoilers
_actuator_effectiveness->updateSetpoint(c[i], i, _control_allocation[i]->_actuator_sp,
_control_allocation[i]->getActuatorMin(), _control_allocation[i]->getActuatorMax());

if (_has_slew_rate) {
_control_allocation[i]->applySlewRateLimit(dt);
}

_control_allocation[i]->clipActuatorSetpoint();
}
}
Expand Down Expand Up @@ -690,15 +692,20 @@ ControlAllocator::publish_actuator_controls()

// Actuator setpoints are shared between Motors or Thrusters. For now, we assume we have only either of them
int actuator_type = 0;

if (_num_actuators[(int)ActuatorType::THRUSTERS] > 0) {
actuator_type = (int)ActuatorType::THRUSTERS;
}

// motors
int motors_idx;
for (motors_idx = 0; motors_idx < _num_actuators[actuator_type] && motors_idx < actuator_motors_s::NUM_CONTROLS; motors_idx++) {

for (motors_idx = 0; motors_idx < _num_actuators[actuator_type]
&& motors_idx < actuator_motors_s::NUM_CONTROLS; motors_idx++) {
int selected_matrix = _control_allocation_selection_indexes[actuator_idx];
float actuator_sp = _control_allocation[selected_matrix]->getActuatorSetpoint()(actuator_idx_matrix[selected_matrix]);
actuator_motors.control[motors_idx] = PX4_ISFINITE(actuator_sp) ? actuator_sp : NAN;

if (stopped_motors & (1u << motors_idx)) {
actuator_motors.control[motors_idx] = NAN;
}
Expand All @@ -717,7 +724,8 @@ ControlAllocator::publish_actuator_controls()
if (_num_actuators[(int)ActuatorType::SERVOS] > 0) {
int servos_idx;

for (servos_idx = 0; servos_idx < _num_actuators[(int)ActuatorType::SERVOS] && servos_idx < actuator_servos_s::NUM_CONTROLS; servos_idx++) {
for (servos_idx = 0; servos_idx < _num_actuators[(int)ActuatorType::SERVOS]
&& servos_idx < actuator_servos_s::NUM_CONTROLS; servos_idx++) {
int selected_matrix = _control_allocation_selection_indexes[actuator_idx];
float actuator_sp = _control_allocation[selected_matrix]->getActuatorSetpoint()(actuator_idx_matrix[selected_matrix]);
actuator_servos.control[servos_idx] = PX4_ISFINITE(actuator_sp) ? actuator_sp : NAN;
Expand Down
15 changes: 9 additions & 6 deletions src/modules/sc_att_control/sc_att_control_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
* @file sc_att_control_main.cpp
* Spacecraft attitude controller.
* Based off the multicopter attitude controller module.
*
*
* @author Pedro Roque, <[email protected]>
*
*/
Expand Down Expand Up @@ -86,7 +86,7 @@ SpacecraftAttitudeControl::parameters_updated()
using math::radians;
_attitude_control.setRateLimit(Vector3f(radians(_param_sc_rollrate_max.get()), radians(_param_sc_pitchrate_max.get()),
radians(_param_sc_yawrate_max.get())));
_man_tilt_max = math::radians(_param_sc_man_tilt_max.get());
_man_tilt_max = math::radians(_param_sc_man_tilt_max.get());
}

void
Expand Down Expand Up @@ -126,6 +126,7 @@ SpacecraftAttitudeControl::generate_attitude_setpoint(const Quatf &q, float dt,
Vector2f v = Vector2f(_man_roll_input_filter.update(_manual_control_setpoint.roll * _man_tilt_max),
-_man_pitch_input_filter.update(_manual_control_setpoint.pitch * _man_tilt_max));
float v_norm = v.norm(); // the norm of v defines the tilt angle

if (v_norm > _man_tilt_max) { // limit to the configured maximum tilt angle
v *= _man_tilt_max / v_norm;
}
Expand Down Expand Up @@ -197,8 +198,8 @@ SpacecraftAttitudeControl::Run()
if (_vehicle_attitude_setpoint_sub.copy(&vehicle_attitude_setpoint)
&& (vehicle_attitude_setpoint.timestamp > _last_attitude_setpoint)) {
/* Removing print
PX4_INFO("Current setpoint: %f %f %f %f", (double)vehicle_attitude_setpoint.q_d[0],
(double)vehicle_attitude_setpoint.q_d[1], (double)vehicle_attitude_setpoint.q_d[2],
PX4_INFO("Current setpoint: %f %f %f %f", (double)vehicle_attitude_setpoint.q_d[0],
(double)vehicle_attitude_setpoint.q_d[1], (double)vehicle_attitude_setpoint.q_d[2],
(double)vehicle_attitude_setpoint.q_d[3]);*/

_attitude_control.setAttitudeSetpoint(Quatf(vehicle_attitude_setpoint.q_d));
Expand Down Expand Up @@ -244,6 +245,7 @@ SpacecraftAttitudeControl::Run()
}

bool attitude_setpoint_generated = false;

if (_vehicle_control_mode.flag_control_attitude_enabled) {

// Generate the attitude setpoint from stick inputs if we are in Manual/Stabilized mode
Expand All @@ -259,11 +261,12 @@ SpacecraftAttitudeControl::Run()
_man_roll_input_filter.reset(0.f);
_man_pitch_input_filter.reset(0.f);
}

Vector3f rates_sp = _attitude_control.update(q);

// publish rate setpoint
vehicle_rates_setpoint_s rates_setpoint{};
rates_setpoint.roll = rates_sp(0);
rates_setpoint.roll = rates_sp(0);
rates_setpoint.pitch = rates_sp(1);
rates_setpoint.yaw = rates_sp(2);
_thrust_setpoint_body.copyTo(rates_setpoint.thrust_body);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -161,19 +161,21 @@ bool ScPositionControl::_inputValid()
return valid;
}

void ScPositionControl::getAttitudeSetpoint(vehicle_attitude_setpoint_s &attitude_setpoint, vehicle_attitude_s &v_att) const
void ScPositionControl::getAttitudeSetpoint(vehicle_attitude_setpoint_s &attitude_setpoint,
vehicle_attitude_s &v_att) const
{
// Set thrust setpoint
attitude_setpoint.thrust_body[0] = _thr_sp(0);
attitude_setpoint.thrust_body[1] = _thr_sp(1);
attitude_setpoint.thrust_body[2] = _thr_sp(2);

// Bypass attitude control by giving same attitude setpoint to att control
if(PX4_ISFINITE(_quat_sp(0)) && PX4_ISFINITE(_quat_sp(1)) && PX4_ISFINITE(_quat_sp(2)) && PX4_ISFINITE(_quat_sp(3)) ) {
if (PX4_ISFINITE(_quat_sp(0)) && PX4_ISFINITE(_quat_sp(1)) && PX4_ISFINITE(_quat_sp(2)) && PX4_ISFINITE(_quat_sp(3))) {
attitude_setpoint.q_d[0] = _quat_sp(0);
attitude_setpoint.q_d[1] = _quat_sp(1);
attitude_setpoint.q_d[2] = _quat_sp(2);
attitude_setpoint.q_d[3] = _quat_sp(3);

} else {
attitude_setpoint.q_d[0] = v_att.q[0];
attitude_setpoint.q_d[1] = v_att.q[1];
Expand Down
20 changes: 14 additions & 6 deletions src/modules/sc_pos_control/SpacecraftPositionControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,9 +93,11 @@ void SpacecraftPositionControl::parameters_update(bool force)

if (responsiveness > 0.6f) {
num_changed += _param_mpc_man_y_tau.commit_no_notification(0.f);

} else {
num_changed += _param_mpc_man_y_tau.commit_no_notification(math::lerp(0.5f, 0.f, responsiveness / 0.6f));
}

num_changed += _param_mpc_jerk_max.commit_no_notification(math::lerp(2.f, 50.f, responsiveness));
num_changed += _param_mpc_jerk_auto.commit_no_notification(math::lerp(1.f, 25.f, responsiveness));
}
Expand Down Expand Up @@ -194,8 +196,10 @@ PositionControlStates SpacecraftPositionControl::set_vehicle_states(const vehicl
_vel_z_deriv.reset();
}

if(PX4_ISFINITE(vehicle_attitude.q[0]) && PX4_ISFINITE(vehicle_attitude.q[1]) && PX4_ISFINITE(vehicle_attitude.q[2]) && PX4_ISFINITE(vehicle_attitude.q[3])) {
if (PX4_ISFINITE(vehicle_attitude.q[0]) && PX4_ISFINITE(vehicle_attitude.q[1]) && PX4_ISFINITE(vehicle_attitude.q[2])
&& PX4_ISFINITE(vehicle_attitude.q[3])) {
states.quaternion = Quatf(vehicle_attitude.q);

} else {
states.quaternion = Quatf();
}
Expand Down Expand Up @@ -298,8 +302,8 @@ void SpacecraftPositionControl::Run()
if ((_setpoint.timestamp < _time_position_control_enabled)
&& (vehicle_local_position.timestamp_sample > _time_position_control_enabled)) {
PX4_INFO("Setpoint time: %f, Vehicle local pos time: %f, Pos Control Enabled time: %f",
(double)_setpoint.timestamp, (double)vehicle_local_position.timestamp_sample,
(double)_time_position_control_enabled);
(double)_setpoint.timestamp, (double)vehicle_local_position.timestamp_sample,
(double)_time_position_control_enabled);
_setpoint = generateFailsafeSetpoint(vehicle_local_position.timestamp_sample, states, false);
}
}
Expand Down Expand Up @@ -347,15 +351,16 @@ void SpacecraftPositionControl::poll_manual_setpoint(const float dt,
if (_vehicle_control_mode.flag_control_attitude_enabled) {
// We are in Stabilized mode
// Generate position setpoints
if(!stabilized_pos_sp_initialized) {
if (!stabilized_pos_sp_initialized) {
// Initialize position setpoint
target_pos_sp = Vector3f(vehicle_local_position.x, vehicle_local_position.y,
vehicle_local_position.z);
vehicle_local_position.z);

const float vehicle_yaw = Eulerf(Quatf(_vehicle_att.q)).psi();
_manual_yaw_sp = vehicle_yaw;
stabilized_pos_sp_initialized = true;
}

// Update velocity setpoint
Vector3f target_vel_sp = Vector3f(_manual_control_setpoint.pitch, _manual_control_setpoint.roll, 0.0);
// TODO(@Pedro-Roque): probably need to move velocity to inertial frame
Expand All @@ -372,9 +377,11 @@ void SpacecraftPositionControl::poll_manual_setpoint(const float dt,

// Generate attitude setpoints
float yaw_sp_move_rate = 0.0;
if (_manual_control_setpoint.throttle > -0.9f){

if (_manual_control_setpoint.throttle > -0.9f) {
yaw_sp_move_rate = _manual_control_setpoint.yaw * yaw_rate;
}

_manual_yaw_sp = wrap_pi(_manual_yaw_sp + yaw_sp_move_rate * dt);
const float roll_body = 0.0;
const float pitch_body = 0.0;
Expand All @@ -383,6 +390,7 @@ void SpacecraftPositionControl::poll_manual_setpoint(const float dt,
q_sp.copyTo(_setpoint.attitude);

_setpoint.timestamp = hrt_absolute_time();

} else {
// We are in Manual mode
stabilized_pos_sp_initialized = false;
Expand Down
2 changes: 1 addition & 1 deletion src/modules/sc_pos_control/SpacecraftPositionControl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -174,7 +174,7 @@ class SpacecraftPositionControl : public ModuleBase<SpacecraftPositionControl>,
* Check for manual setpoints.
*/
void poll_manual_setpoint(const float dt, const vehicle_local_position_s
&vehicle_local_position, const vehicle_attitude_s &_vehicle_att);
&vehicle_local_position, const vehicle_attitude_s &_vehicle_att);

/**
* Generate setpoint to bridge no executable setpoint being available.
Expand Down
Loading

0 comments on commit 697bcde

Please sign in to comment.