msg: remove unused vehicle_actuator_setpoint topic

This commit is contained in:
Beat Küng 2021-11-10 10:26:09 +01:00 committed by Daniel Agar
parent 52a2ef34fd
commit a0e43bca96
7 changed files with 4 additions and 33 deletions

View File

@ -164,7 +164,6 @@ set(msg_files
ulog_stream.msg
ulog_stream_ack.msg
vehicle_acceleration.msg
vehicle_actuator_setpoint.msg
vehicle_air_data.msg
vehicle_angular_acceleration.msg
vehicle_angular_acceleration_setpoint.msg

View File

@ -1,6 +0,0 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp the data this control response is based on was sampled
uint8 NUM_ACTUATOR_SETPOINT = 16
float32[16] actuator

View File

@ -44,7 +44,6 @@
#include <ControlAllocation/ControlAllocation.hpp>
#include <matrix/matrix/math.hpp>
#include <uORB/topics/vehicle_actuator_setpoint.h>
class ActuatorEffectiveness
{

View File

@ -70,7 +70,6 @@
#pragma once
#include <matrix/matrix/math.hpp>
#include <uORB/topics/vehicle_actuator_setpoint.h>
class ControlAllocation
{

View File

@ -335,13 +335,10 @@ ControlAllocator::Run()
_control_allocation->allocate();
// Publish actuator setpoint and allocator status
publish_actuator_setpoint();
publish_actuator_controls();
publish_control_allocator_status();
// Publish on legacy topics for compatibility with
// the current mixer system and multicopter controller
// TODO: remove
publish_legacy_actuator_controls();
}
perf_end(_loop_perf);
@ -373,19 +370,6 @@ ControlAllocator::update_effectiveness_matrix_if_needed(bool force)
}
}
void
ControlAllocator::publish_actuator_setpoint()
{
matrix::Vector<float, NUM_ACTUATORS> actuator_sp = _control_allocation->getActuatorSetpoint();
vehicle_actuator_setpoint_s vehicle_actuator_setpoint{};
vehicle_actuator_setpoint.timestamp = hrt_absolute_time();
vehicle_actuator_setpoint.timestamp_sample = _timestamp_sample;
actuator_sp.copyTo(vehicle_actuator_setpoint.actuator);
_vehicle_actuator_setpoint_pub.publish(vehicle_actuator_setpoint);
}
void
ControlAllocator::publish_control_allocator_status()
{
@ -434,7 +418,7 @@ ControlAllocator::publish_control_allocator_status()
}
void
ControlAllocator::publish_legacy_actuator_controls()
ControlAllocator::publish_actuator_controls()
{
actuator_motors_s actuator_motors;
actuator_motors.timestamp = hrt_absolute_time();

View File

@ -67,7 +67,6 @@
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/vehicle_torque_setpoint.h>
#include <uORB/topics/vehicle_thrust_setpoint.h>
#include <uORB/topics/vehicle_actuator_setpoint.h>
#include <uORB/topics/vehicle_status.h>
class ControlAllocator : public ModuleBase<ControlAllocator>, public ModuleParams, public px4::WorkItem
@ -108,10 +107,9 @@ private:
void update_effectiveness_matrix_if_needed(bool force = false);
void publish_actuator_setpoint();
void publish_control_allocator_status();
void publish_legacy_actuator_controls();
void publish_actuator_controls();
enum class AllocationMethod {
NONE = -1,
@ -137,7 +135,6 @@ private:
uORB::SubscriptionCallbackWorkItem _vehicle_thrust_setpoint_sub{this, ORB_ID(vehicle_thrust_setpoint)}; /**< vehicle thrust setpoint subscription */
// Outputs
uORB::Publication<vehicle_actuator_setpoint_s> _vehicle_actuator_setpoint_pub{ORB_ID(vehicle_actuator_setpoint)}; /**< actuator setpoint publication */
uORB::Publication<control_allocator_status_s> _control_allocator_status_pub{ORB_ID(control_allocator_status)}; /**< actuator setpoint publication */
uORB::Publication<actuator_motors_s> _actuator_motors_pub{ORB_ID(actuator_motors)};

View File

@ -198,7 +198,6 @@ void LoggedTopics::add_default_topics()
if (sys_ctrl_alloc >= 1) {
add_topic("actuator_motors", 100);
add_topic("actuator_servos", 100);
add_topic("vehicle_actuator_setpoint", 20);
add_topic("vehicle_angular_acceleration", 20);
add_topic("vehicle_angular_acceleration_setpoint", 20);
add_topic("vehicle_thrust_setpoint", 20);