cleanup subscribers and publishers

This commit is contained in:
chfriedrich98 2024-03-25 11:04:06 +01:00
parent a200a446c7
commit 5f1edc883d
6 changed files with 17 additions and 39 deletions

View File

@ -41,16 +41,12 @@
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
// uORB includes
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_motors.h>
#include <uORB/PublicationMulti.hpp>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionMultiArray.hpp>
#include <uORB/topics/differential_drive_setpoint.h>
// Standard library includes
@ -58,7 +54,7 @@
// Local includes
#include "AckermannDriveControl/AckermannDriveControl.hpp"
//#include "AckermannDriveGuidance/AckermannDriveGuidance.hpp"
//#include "AckermannDriveGuidance/AckermannDriveGuidance.hpp" //TO BE IMPLEMENTED
#include "AckermannDriveKinematics/AckermannDriveKinematics.hpp"
using namespace time_literals;
@ -96,7 +92,7 @@ private:
uORB::Publication<differential_drive_setpoint_s> _differential_drive_setpoint_pub{ORB_ID(differential_drive_setpoint)};
AckermannDriveControl _ackermann_drive_control{this};
//AckermannDriveGuidance _ackermann_drive_guidance{this};
//AckermannDriveGuidance _ackermann_drive_guidance{this}; // TO BE IMPLEMENTED
AckermannDriveKinematics _ackermann_drive_kinematics{this};
bool _armed = false;
@ -109,7 +105,6 @@ private:
(ParamFloat<px4::params::RDD_ANG_SCALE>) _param_rdd_ang_velocity_scale,
(ParamFloat<px4::params::RDD_WHEEL_SPEED>) _param_rdd_max_wheel_speed,
(ParamFloat<px4::params::RDD_WHEEL_BASE>) _param_rdd_wheel_base,
(ParamFloat<px4::params::RDD_WHEEL_RADIUS>) _param_rdd_wheel_radius,
(ParamInt<px4::params::CA_R_REV>) _param_r_rev
(ParamFloat<px4::params::RDD_WHEEL_RADIUS>) _param_rdd_wheel_radius
)
};

View File

@ -34,7 +34,6 @@
#include "AckermannDriveControl.hpp"
using namespace time_literals;
using namespace matrix;
AckermannDriveControl::AckermannDriveControl(ModuleParams *parent) : ModuleParams(parent)
{

View File

@ -41,24 +41,14 @@
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
// uORB includes
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_motors.h>
#include <uORB/topics/actuator_servos.h>
#include <uORB/PublicationMulti.hpp>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionMultiArray.hpp>
#include <uORB/topics/differential_drive_setpoint.h>
// Standard library includespr
// Standard library
#include <math.h>
// Local includes
// #include <AckermannDriveKinematics.hpp>
class AckermannDriveControl : public ModuleParams
{
public:
@ -78,13 +68,4 @@ private:
uORB::Publication<differential_drive_setpoint_s> _differential_drive_setpoint_pub{ORB_ID(differential_drive_setpoint)};
differential_drive_setpoint_s _differential_drive_setpoint{};
DEFINE_PARAMETERS(
(ParamFloat<px4::params::RDD_SPEED_SCALE>) _param_rdd_speed_scale,
(ParamFloat<px4::params::RDD_ANG_SCALE>) _param_rdd_ang_velocity_scale,
(ParamFloat<px4::params::RDD_WHEEL_SPEED>) _param_rdd_max_wheel_speed,
(ParamFloat<px4::params::RDD_WHEEL_BASE>) _param_rdd_wheel_base,
(ParamFloat<px4::params::RDD_WHEEL_RADIUS>) _param_rdd_wheel_radius,
(ParamInt<px4::params::CA_R_REV>) _param_r_rev
)
};

View File

@ -52,7 +52,7 @@ void AckermannDriveKinematics::allocate()
hrt_abstime now = hrt_absolute_time();
actuator_motors_s actuator_motors{};
actuator_motors.reversible_flags = _param_r_rev.get(); // should be 3 see rc.rover_differential_defaults
actuator_motors.reversible_flags = _param_r_rev.get();
actuator_motors.control[0] = speed;
actuator_motors.control[1] = speed;
actuator_motors.timestamp = now;

View File

@ -33,14 +33,19 @@
#pragma once
#include <matrix/matrix/math.hpp>
//px4 includes
#include <px4_platform_common/module_params.h>
// uORB includes
#include <uORB/PublicationMulti.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/actuator_motors.h>
#include <uORB/topics/actuator_servos.h>
#include <uORB/topics/differential_drive_setpoint.h>
//standard includes
#include <matrix/matrix/math.hpp>
/**
* @brief Differential Drive Kinematics class for computing the kinematics of a differential drive robot.
*
@ -63,9 +68,6 @@ private:
differential_drive_setpoint_s _differential_drive_control_output{};
float _max_speed{0.f};
float _max_angular_velocity{0.f};
DEFINE_PARAMETERS(
(ParamInt<px4::params::CA_R_REV>) _param_r_rev
)

View File

@ -31,9 +31,9 @@
#
############################################################################
add_subdirectory(AckermannDriveKinematics)
add_subdirectory(AckermannDriveControl)
add_subdirectory(AckermannDriveKinematics)
#add_subdirectory(AckermannDriveGuidance) #TO BE IMPLEMENTED
px4_add_module(
MODULE modules__ackermann_drive
@ -44,7 +44,8 @@ px4_add_module(
DEPENDS
AckermannDriveControl
AckermannDriveKinematics
#AckermannDriveGuidance #TO BE IMPLEMENTED
px4_work_queue
# MODULE_CONFIG
# module.yaml
#MODULE_CONFIG
# module.yaml
)