cleanup + updated acro

This commit is contained in:
PerFrivik 2024-01-30 14:48:53 +01:00 committed by Matthias Grob
parent f996caa5bd
commit 560d6a9d4b
3 changed files with 10 additions and 3 deletions

View File

@ -84,11 +84,18 @@ void DifferentialDrive::Run()
if (_vehicle_control_mode_sub.copy(&vehicle_control_mode)) { if (_vehicle_control_mode_sub.copy(&vehicle_control_mode)) {
_differential_drive_kinematics.setArmed(vehicle_control_mode.flag_armed); _differential_drive_kinematics.setArmed(vehicle_control_mode.flag_armed);
_manual_driving = vehicle_control_mode.flag_control_manual_enabled; _manual_driving = vehicle_control_mode.flag_control_manual_enabled;
_acro_driving = vehicle_control_mode.flag_control_rates_enabled;
_mission_driving = vehicle_control_mode.flag_control_auto_enabled; _mission_driving = vehicle_control_mode.flag_control_auto_enabled;
} }
} }
if (_vehicle_status_sub.updated()) {
vehicle_status_s vehicle_status{};
if (_vehicle_status_sub.copy(&vehicle_status)) {
_acro_driving = (vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_ACRO);
}
}
if (_manual_driving) { if (_manual_driving) {
// Manual mode // Manual mode
// directly produce setpoints from the manual control setpoint (joystick) // directly produce setpoints from the manual control setpoint (joystick)

View File

@ -44,6 +44,7 @@
#include <uORB/topics/manual_control_setpoint.h> #include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/parameter_update.h> #include <uORB/topics/parameter_update.h>
#include <uORB/topics/vehicle_control_mode.h> #include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_status.h>
#include "DifferentialDriveControl/DifferentialDriveControl.hpp" #include "DifferentialDriveControl/DifferentialDriveControl.hpp"
#include "DifferentialDriveGuidance/DifferentialDriveGuidance.hpp" #include "DifferentialDriveGuidance/DifferentialDriveGuidance.hpp"
@ -78,6 +79,7 @@ private:
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};
uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)};
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
uORB::Publication<differential_drive_setpoint_s> _differential_drive_setpoint_pub{ORB_ID(differential_drive_setpoint)}; uORB::Publication<differential_drive_setpoint_s> _differential_drive_setpoint_pub{ORB_ID(differential_drive_setpoint)};
bool _manual_driving = false; bool _manual_driving = false;

View File

@ -40,8 +40,6 @@
#include <mathlib/mathlib.h> #include <mathlib/mathlib.h>
#include <lib/geo/geo.h> #include <lib/geo/geo.h>
#include <math.h> #include <math.h>
#include <chrono>
// #include <matrix/matrix/Matrix.hpp>
#include <lib/motion_planning/PositionSmoothing.hpp> #include <lib/motion_planning/PositionSmoothing.hpp>
#include <lib/motion_planning/VelocitySmoothing.hpp> #include <lib/motion_planning/VelocitySmoothing.hpp>