mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Make sure vehicle_thrust_setpoint is always published before vehicle_torque_setpoint
After f0b05ea7cfd9de4113f4cd63e8068cf8089bc158 the control allocator only has a callback on the torque setpoint and even though this should work I'm paranoid and would like to avoid surprises by always publishing the thrust before torque then the samples that were published together are also allocated together.
This commit is contained in:
parent
ff2b82dc51
commit
fdc4766da6
@ -126,8 +126,8 @@ AirshipAttitudeControl::Run()
|
||||
if (_vehicle_angular_velocity_sub.update(&angular_velocity)) {
|
||||
|
||||
/* run the rate controller immediately after a gyro update */
|
||||
publishTorqueSetpoint(angular_velocity.timestamp_sample);
|
||||
publishThrustSetpoint(angular_velocity.timestamp_sample);
|
||||
publishTorqueSetpoint(angular_velocity.timestamp_sample);
|
||||
|
||||
/* check for updates in manual control topic */
|
||||
_manual_control_setpoint_sub.update(&_manual_control_setpoint);
|
||||
|
||||
@ -44,8 +44,8 @@ FixedwingRateControl::FixedwingRateControl(bool vtol) :
|
||||
ModuleParams(nullptr),
|
||||
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::nav_and_controllers),
|
||||
_actuator_controls_status_pub(vtol ? ORB_ID(actuator_controls_status_1) : ORB_ID(actuator_controls_status_0)),
|
||||
_vehicle_torque_setpoint_pub(vtol ? ORB_ID(vehicle_torque_setpoint_virtual_fw) : ORB_ID(vehicle_torque_setpoint)),
|
||||
_vehicle_thrust_setpoint_pub(vtol ? ORB_ID(vehicle_thrust_setpoint_virtual_fw) : ORB_ID(vehicle_thrust_setpoint)),
|
||||
_vehicle_torque_setpoint_pub(vtol ? ORB_ID(vehicle_torque_setpoint_virtual_fw) : ORB_ID(vehicle_torque_setpoint)),
|
||||
_loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle"))
|
||||
{
|
||||
_handle_param_vt_fw_difthr_en = param_find("VT_FW_DIFTHR_EN");
|
||||
|
||||
@ -116,8 +116,8 @@ private:
|
||||
uORB::Publication<actuator_controls_status_s> _actuator_controls_status_pub;
|
||||
uORB::Publication<vehicle_rates_setpoint_s> _rate_sp_pub{ORB_ID(vehicle_rates_setpoint)};
|
||||
uORB::PublicationMulti<rate_ctrl_status_s> _rate_ctrl_status_pub{ORB_ID(rate_ctrl_status)};
|
||||
uORB::Publication<vehicle_torque_setpoint_s> _vehicle_torque_setpoint_pub;
|
||||
uORB::Publication<vehicle_thrust_setpoint_s> _vehicle_thrust_setpoint_pub;
|
||||
uORB::Publication<vehicle_torque_setpoint_s> _vehicle_torque_setpoint_pub;
|
||||
uORB::Publication<normalized_unsigned_setpoint_s> _flaps_setpoint_pub{ORB_ID(flaps_setpoint)};
|
||||
uORB::Publication<normalized_unsigned_setpoint_s> _spoilers_setpoint_pub{ORB_ID(spoilers_setpoint)};
|
||||
|
||||
|
||||
@ -46,8 +46,8 @@ using math::radians;
|
||||
MulticopterRateControl::MulticopterRateControl(bool vtol) :
|
||||
ModuleParams(nullptr),
|
||||
WorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl),
|
||||
_vehicle_torque_setpoint_pub(vtol ? ORB_ID(vehicle_torque_setpoint_virtual_mc) : ORB_ID(vehicle_torque_setpoint)),
|
||||
_vehicle_thrust_setpoint_pub(vtol ? ORB_ID(vehicle_thrust_setpoint_virtual_mc) : ORB_ID(vehicle_thrust_setpoint)),
|
||||
_vehicle_torque_setpoint_pub(vtol ? ORB_ID(vehicle_torque_setpoint_virtual_mc) : ORB_ID(vehicle_torque_setpoint)),
|
||||
_loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle"))
|
||||
{
|
||||
_vehicle_status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_ROTARY_WING;
|
||||
|
||||
@ -107,8 +107,8 @@ private:
|
||||
uORB::Publication<actuator_controls_status_s> _actuator_controls_status_pub{ORB_ID(actuator_controls_status_0)};
|
||||
uORB::PublicationMulti<rate_ctrl_status_s> _controller_status_pub{ORB_ID(rate_ctrl_status)};
|
||||
uORB::Publication<vehicle_rates_setpoint_s> _vehicle_rates_setpoint_pub{ORB_ID(vehicle_rates_setpoint)};
|
||||
uORB::Publication<vehicle_torque_setpoint_s> _vehicle_torque_setpoint_pub;
|
||||
uORB::Publication<vehicle_thrust_setpoint_s> _vehicle_thrust_setpoint_pub;
|
||||
uORB::Publication<vehicle_torque_setpoint_s> _vehicle_torque_setpoint_pub;
|
||||
|
||||
vehicle_control_mode_s _vehicle_control_mode{};
|
||||
vehicle_status_s _vehicle_status{};
|
||||
|
||||
@ -81,8 +81,8 @@ VtolAttitudeControl::VtolAttitudeControl() :
|
||||
_spoilers_setpoint_pub.advertise();
|
||||
_vtol_vehicle_status_pub.advertise();
|
||||
_vehicle_thrust_setpoint0_pub.advertise();
|
||||
_vehicle_torque_setpoint0_pub.advertise();
|
||||
_vehicle_thrust_setpoint1_pub.advertise();
|
||||
_vehicle_torque_setpoint0_pub.advertise();
|
||||
_vehicle_torque_setpoint1_pub.advertise();
|
||||
}
|
||||
|
||||
@ -449,10 +449,10 @@ VtolAttitudeControl::Run()
|
||||
|
||||
_vtol_type->fill_actuator_outputs();
|
||||
|
||||
_vehicle_torque_setpoint0_pub.publish(_torque_setpoint_0);
|
||||
_vehicle_torque_setpoint1_pub.publish(_torque_setpoint_1);
|
||||
_vehicle_thrust_setpoint0_pub.publish(_thrust_setpoint_0);
|
||||
_vehicle_thrust_setpoint1_pub.publish(_thrust_setpoint_1);
|
||||
_vehicle_torque_setpoint0_pub.publish(_torque_setpoint_0);
|
||||
_vehicle_torque_setpoint1_pub.publish(_torque_setpoint_1);
|
||||
|
||||
// Advertise/publish vtol vehicle status -- immediately if changed, otherwise at 1 Hz
|
||||
const bool vtol_vehicle_status_changed =
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user