mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
px4_module: use px4_atomic_t
This commit is contained in:
parent
b6e2ac74de
commit
481bfc6308
@ -132,13 +132,13 @@ int BATT_SMBUS::task_spawn(int argc, char *argv[])
|
||||
|
||||
for (unsigned i = 0; i < NUM_BUS_OPTIONS; i++) {
|
||||
|
||||
if (_object == nullptr && (busid == BATT_SMBUS_BUS_ALL || bus_options[i].busid == busid)) {
|
||||
if (!is_running() && (busid == BATT_SMBUS_BUS_ALL || bus_options[i].busid == busid)) {
|
||||
|
||||
SMBus *interface = new SMBus(bus_options[i].busnum, BATT_SMBUS_ADDR);
|
||||
BATT_SMBUS *dev = new BATT_SMBUS(interface, bus_options[i].devpath);
|
||||
|
||||
// Successful read of device type, we've found our battery
|
||||
_object = dev;
|
||||
_object.store(dev);
|
||||
_task_id = task_id_is_work_queue;
|
||||
|
||||
int result = dev->get_startup_info();
|
||||
|
||||
@ -92,7 +92,7 @@ int Heater::controller_period(char *argv[])
|
||||
int Heater::custom_command(int argc, char *argv[])
|
||||
{
|
||||
// Check if the driver is running.
|
||||
if (!is_running() && !_object) {
|
||||
if (!is_running()) {
|
||||
PX4_INFO("not running");
|
||||
return PX4_ERROR;
|
||||
}
|
||||
@ -240,7 +240,7 @@ void Heater::initialize_trampoline(void *argv)
|
||||
return;
|
||||
}
|
||||
|
||||
_object = heater;
|
||||
_object.store(heater);
|
||||
heater->start();
|
||||
}
|
||||
|
||||
|
||||
@ -1008,7 +1008,7 @@ PX4FMU::cycle_trampoline(void *arg)
|
||||
return;
|
||||
}
|
||||
|
||||
_object = dev;
|
||||
_object.store(dev);
|
||||
}
|
||||
|
||||
dev->cycle();
|
||||
|
||||
@ -189,7 +189,7 @@ RCInput::cycle_trampoline(void *arg)
|
||||
return;
|
||||
}
|
||||
|
||||
_object = dev;
|
||||
_object.store(dev);
|
||||
}
|
||||
|
||||
dev->cycle();
|
||||
|
||||
@ -113,7 +113,7 @@ void SendEvent::initialize_trampoline(void *arg)
|
||||
}
|
||||
|
||||
send_event->start();
|
||||
_object = send_event;
|
||||
_object.store(send_event);
|
||||
}
|
||||
|
||||
void SendEvent::cycle_trampoline(void *arg)
|
||||
|
||||
@ -92,7 +92,7 @@ void LandDetector::_cycle()
|
||||
{
|
||||
perf_begin(_cycle_perf);
|
||||
|
||||
if (_object == nullptr) { // not initialized yet
|
||||
if (_object.load() == nullptr) { // not initialized yet
|
||||
// Advertise the first land detected uORB.
|
||||
_landDetected.timestamp = hrt_absolute_time();
|
||||
_landDetected.freefall = false;
|
||||
@ -110,7 +110,7 @@ void LandDetector::_cycle()
|
||||
|
||||
_check_params(true);
|
||||
|
||||
_object = this;
|
||||
_object.store(this);
|
||||
}
|
||||
|
||||
_check_params(false);
|
||||
|
||||
@ -151,7 +151,7 @@ int LoadMon::task_spawn(int argc, char *argv[])
|
||||
return ret;
|
||||
}
|
||||
|
||||
_object = obj;
|
||||
_object.store(obj);
|
||||
_task_id = task_id_is_work_queue;
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -173,7 +173,7 @@ WindEstimatorModule::cycle_trampoline(void *arg)
|
||||
return;
|
||||
}
|
||||
|
||||
_object = dev;
|
||||
_object.store(dev);
|
||||
}
|
||||
|
||||
if (dev) {
|
||||
|
||||
@ -41,6 +41,7 @@
|
||||
#include <unistd.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#include <px4_atomic.h>
|
||||
#include <px4_time.h>
|
||||
#include <px4_log.h>
|
||||
#include <px4_tasks.h>
|
||||
@ -174,10 +175,10 @@ public:
|
||||
argv += 1;
|
||||
#endif
|
||||
|
||||
_object = T::instantiate(argc, argv);
|
||||
T *object = T::instantiate(argc, argv);
|
||||
_object.store(object);
|
||||
|
||||
if (_object) {
|
||||
T *object = (T *)_object;
|
||||
if (object) {
|
||||
object->run();
|
||||
|
||||
} else {
|
||||
@ -229,8 +230,9 @@ public:
|
||||
lock_module();
|
||||
|
||||
if (is_running()) {
|
||||
if (_object) {
|
||||
T *object = (T *)_object;
|
||||
T *object = _object.load();
|
||||
|
||||
if (object) {
|
||||
object->request_stop();
|
||||
|
||||
unsigned int i = 0;
|
||||
@ -247,10 +249,8 @@ public:
|
||||
|
||||
_task_id = -1;
|
||||
|
||||
if (_object) {
|
||||
delete _object;
|
||||
_object = nullptr;
|
||||
}
|
||||
delete _object.load();
|
||||
_object.store(nullptr);
|
||||
|
||||
ret = -1;
|
||||
break;
|
||||
@ -279,8 +279,8 @@ public:
|
||||
int ret = -1;
|
||||
lock_module();
|
||||
|
||||
if (is_running() && _object) {
|
||||
T *object = (T *)_object;
|
||||
if (is_running() && _object.load()) {
|
||||
T *object = _object.load();
|
||||
ret = object->print_status();
|
||||
|
||||
} else {
|
||||
@ -326,7 +326,7 @@ protected:
|
||||
*/
|
||||
virtual void request_stop()
|
||||
{
|
||||
_task_should_exit = true;
|
||||
_task_should_exit.store(true);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -335,7 +335,7 @@ protected:
|
||||
*/
|
||||
bool should_exit() const
|
||||
{
|
||||
return _task_should_exit;
|
||||
return _task_should_exit.load();
|
||||
}
|
||||
|
||||
/**
|
||||
@ -351,10 +351,8 @@ protected:
|
||||
// - deleting the object must take place inside the lock.
|
||||
lock_module();
|
||||
|
||||
if (_object) {
|
||||
delete _object;
|
||||
_object = nullptr;
|
||||
}
|
||||
delete _object.load();
|
||||
_object.store(nullptr);
|
||||
|
||||
_task_id = -1; // Signal a potentially waiting thread for the module to exit that it can continue.
|
||||
unlock_module();
|
||||
@ -372,7 +370,7 @@ protected:
|
||||
/* Wait up to 1s. */
|
||||
px4_usleep(2500);
|
||||
|
||||
} while (!_object && ++i < 400);
|
||||
} while (!_object.load() && ++i < 400);
|
||||
|
||||
if (i == 400) {
|
||||
PX4_ERR("Timed out while waiting for thread to start");
|
||||
@ -387,14 +385,14 @@ protected:
|
||||
*/
|
||||
static T *get_instance()
|
||||
{
|
||||
return (T *)_object;
|
||||
return (T *)_object.load();
|
||||
}
|
||||
|
||||
/**
|
||||
* @var _object Instance if the module is running.
|
||||
* @note There will be one instance for each template type.
|
||||
*/
|
||||
static volatile T *_object;
|
||||
static px4::atomic<T *> _object;
|
||||
|
||||
/** @var _task_id The task handle: -1 = invalid, otherwise task is assumed to be running. */
|
||||
static int _task_id;
|
||||
@ -420,11 +418,11 @@ private:
|
||||
}
|
||||
|
||||
/** @var _task_should_exit Boolean flag to indicate if the task should exit. */
|
||||
volatile bool _task_should_exit = false;
|
||||
px4::atomic_bool _task_should_exit{false};
|
||||
};
|
||||
|
||||
template<class T>
|
||||
volatile T *ModuleBase<T>::_object = nullptr;
|
||||
px4::atomic<T *> ModuleBase<T>::_object{nullptr};
|
||||
|
||||
template<class T>
|
||||
int ModuleBase<T>::_task_id = -1;
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user