PX4 Firmware
PX4 Autopilot Software http://px4.io
dataman.cpp File Reference

DATAMANAGER driver. More...

#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/tasks.h>
#include <px4_platform_common/getopt.h>
#include <drivers/drv_hrt.h>
#include <lib/parameters/param.h>
#include <lib/perf/perf_counter.h>
#include "dataman.h"
Include dependency graph for dataman.cpp:

Go to the source code of this file.

Classes

struct  dm_operations_t
 
struct  work_q_item_t
 Work task work item. More...
 
struct  work_q_t
 

Macros

#define DM_SECTOR_HDR_SIZE   4 /* data manager per item header overhead */
 

Typedefs

typedef struct dm_operations_t dm_operations_t
 

Enumerations

enum  dm_function_t {
  dm_write_func = 0, dm_read_func, dm_clear_func, dm_restart_func,
  dm_number_of_funcs
}
 Types of function calls supported by the worker task. More...
 
enum  { BACKEND_NONE = 0, BACKEND_FILE, BACKEND_RAM, BACKEND_LAST }
 

Functions

__BEGIN_DECLS __EXPORT int dataman_main (int argc, char *argv[])
 
static ssize_t _file_write (dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count)
 
static ssize_t _file_read (dm_item_t item, unsigned index, void *buf, size_t count)
 
static int _file_clear (dm_item_t item)
 
static int _file_restart (dm_reset_reason reason)
 
static int _file_initialize (unsigned max_offset)
 
static void _file_shutdown ()
 
static ssize_t _ram_write (dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count)
 
static ssize_t _ram_read (dm_item_t item, unsigned index, void *buf, size_t count)
 
static int _ram_clear (dm_item_t item)
 
static int _ram_restart (dm_reset_reason reason)
 
static int _ram_initialize (unsigned max_offset)
 
static void _ram_shutdown ()
 
static void init_q (work_q_t *q)
 
static void destroy_q (work_q_t *q)
 
static void lock_queue (work_q_t *q)
 
static void unlock_queue (work_q_t *q)
 
static work_q_item_tcreate_work_item ()
 
static void destroy_work_item (work_q_item_t *item)
 
static work_q_item_tdequeue_work_item ()
 
static int enqueue_work_item_and_wait_for_result (work_q_item_t *item)
 
static bool is_running ()
 
static int calculate_offset (dm_item_t item, unsigned index)
 
__EXPORT ssize_t dm_write (dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count)
 Write to the data manager file. More...
 
__EXPORT ssize_t dm_read (dm_item_t item, unsigned index, void *buf, size_t count)
 Retrieve from the data manager file. More...
 
__EXPORT int dm_clear (dm_item_t item)
 Clear a data Item. More...
 
__EXPORT int dm_lock (dm_item_t item)
 Lock all items of a type. More...
 
__EXPORT int dm_trylock (dm_item_t item)
 Try to lock all items of a type (. More...
 
__EXPORT void dm_unlock (dm_item_t item)
 Unlock a data Item. More...
 
__EXPORT int dm_restart (dm_reset_reason reason)
 Tell the data manager about the type of the last reset. More...
 
static int task_main (int argc, char *argv[])
 
static int start ()
 
static void status ()
 
static void stop ()
 
static void usage ()
 
static int backend_check ()
 

Variables

static __END_DECLS constexpr int TASK_STACK_SIZE = 1220
 
static constexpr dm_operations_t dm_file_operations
 
static constexpr dm_operations_t dm_ram_operations
 
static const dm_operations_tg_dm_ops
 
struct {
   union {
      struct {
         int   fd
 
      }   file
 
      struct {
         uint8_t *   data
 
         uint8_t *   data_end
 
      }   ram
 
   } 
 
   bool   running
 
dm_operations_data
 
const size_t k_work_item_allocation_chunk_size = 8
 
static unsigned g_func_counts [dm_number_of_funcs]
 
static const unsigned g_per_item_max_index [DM_KEY_NUM_KEYS]
 
static constexpr size_t g_per_item_size [DM_KEY_NUM_KEYS]
 
static unsigned int g_key_offsets [DM_KEY_NUM_KEYS]
 
static px4_sem_t * g_item_locks [DM_KEY_NUM_KEYS]
 
static px4_sem_t g_sys_state_mutex_mission
 
static px4_sem_t g_sys_state_mutex_fence
 
static perf_counter_t _dm_read_perf {nullptr}
 
static perf_counter_t _dm_write_perf {nullptr}
 
static const char * default_device_path = PX4_STORAGEDIR "/dataman"
 
static char * k_data_manager_device_path = nullptr
 
static enum { ... }  backend = BACKEND_NONE
 
static work_q_t g_free_q
 
static work_q_t g_work_q
 
static px4_sem_t g_work_queued_sema
 
static px4_sem_t g_init_sema
 
static bool g_task_should_exit
 if true, dataman task should exit More...
 

Detailed Description

DATAMANAGER driver.

Author
Jean Cyr
Lorenz Meier
Julian Oes
Thomas Gubler
David Sidrane

Definition in file dataman.cpp.

Macro Definition Documentation

◆ DM_SECTOR_HDR_SIZE

#define DM_SECTOR_HDR_SIZE   4 /* data manager per item header overhead */

Definition at line 219 of file dataman.cpp.

Referenced by _file_write().

Typedef Documentation

◆ dm_operations_t

Enumeration Type Documentation

◆ anonymous enum

anonymous enum
Enumerator
BACKEND_NONE 
BACKEND_FILE 
BACKEND_RAM 
BACKEND_LAST 

Definition at line 251 of file dataman.cpp.

◆ dm_function_t

Types of function calls supported by the worker task.

Enumerator
dm_write_func 
dm_read_func 
dm_clear_func 
dm_restart_func 
dm_number_of_funcs 

Definition at line 165 of file dataman.cpp.

Function Documentation

◆ _file_clear()

static int _file_clear ( dm_item_t  item)
static

Definition at line 698 of file dataman.cpp.

References calculate_offset(), dm_operations_t::clear, dm_operations_data, dm_ram_operations, g_per_item_max_index, g_per_item_size, dm_operations_t::read, and dm_operations_t::write.

Here is the call graph for this function:

◆ _file_initialize()

static int _file_initialize ( unsigned  max_offset)
static

◆ _file_read()

static ssize_t _file_read ( dm_item_t  item,
unsigned  index,
void *  buf,
size_t  count 
)
static

Definition at line 607 of file dataman.cpp.

References calculate_offset(), DM_KEY_NUM_KEYS, dm_operations_data, dm_ram_operations, g_per_item_size, and dm_operations_t::read.

Here is the call graph for this function:

◆ _file_restart()

◆ _file_shutdown()

static void _file_shutdown ( )
static

Definition at line 997 of file dataman.cpp.

References dm_operations_data.

◆ _file_write()

static ssize_t _file_write ( dm_item_t  item,
unsigned  index,
dm_persitence_t  persistence,
const void *  buf,
size_t  count 
)
static

Definition at line 490 of file dataman.cpp.

References calculate_offset(), dm_operations_data, DM_PERSIST_POWER_ON_RESET, dm_ram_operations, DM_SECTOR_HDR_SIZE, g_per_item_size, and dm_operations_t::write.

Here is the call graph for this function:

◆ _ram_clear()

static int _ram_clear ( dm_item_t  item)
static

Definition at line 668 of file dataman.cpp.

References calculate_offset(), dm_operations_data, g_per_item_max_index, and g_per_item_size.

Here is the call graph for this function:

◆ _ram_initialize()

◆ _ram_read()

static ssize_t _ram_read ( dm_item_t  item,
unsigned  index,
void *  buf,
size_t  count 
)
static

Definition at line 567 of file dataman.cpp.

References calculate_offset(), dm_operations_data, and g_per_item_size.

Here is the call graph for this function:

◆ _ram_restart()

◆ _ram_shutdown()

static void _ram_shutdown ( )
static

Definition at line 1004 of file dataman.cpp.

References dm_operations_data, dm_ram_operations, and dm_operations_t::shutdown.

◆ _ram_write()

static ssize_t _ram_write ( dm_item_t  item,
unsigned  index,
dm_persitence_t  persistence,
const void *  buf,
size_t  count 
)
static

Definition at line 451 of file dataman.cpp.

References calculate_offset(), dm_operations_data, and g_per_item_size.

Here is the call graph for this function:

◆ backend_check()

static int backend_check ( )
static

Definition at line 1537 of file dataman.cpp.

References BACKEND_NONE, and usage().

Referenced by dataman_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ calculate_offset()

static int calculate_offset ( dm_item_t  item,
unsigned  index 
)
static

Definition at line 422 of file dataman.cpp.

References DM_KEY_NUM_KEYS, g_per_item_max_index, and g_per_item_size.

Referenced by _file_clear(), _file_read(), _file_write(), _ram_clear(), _ram_read(), and _ram_write().

Here is the caller graph for this function:

◆ create_work_item()

static work_q_item_t* create_work_item ( )
static

Definition at line 304 of file dataman.cpp.

References work_q_item_t::first, k_work_item_allocation_chunk_size, lock_queue(), work_q_t::max_size, work_q_t::q, work_q_t::size, unlock_queue(), and work_q_item_t::wait_sem.

Referenced by dm_clear(), dm_read(), dm_restart(), and dm_write().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dataman_main()

int dataman_main ( int  argc,
char *  argv[] 
)

Definition at line 1549 of file dataman.cpp.

References backend_check(), BACKEND_FILE, BACKEND_NONE, BACKEND_RAM, DM_INIT_REASON_IN_FLIGHT, DM_INIT_REASON_POWER_ON, dm_restart(), is_running(), start(), status(), stop(), and usage().

Here is the call graph for this function:

◆ dequeue_work_item()

static work_q_item_t* dequeue_work_item ( )
inlinestatic

Definition at line 373 of file dataman.cpp.

References lock_queue(), work_q_t::q, work_q_t::size, and unlock_queue().

Referenced by task_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ destroy_q()

static void destroy_q ( work_q_t q)
inlinestatic

Definition at line 286 of file dataman.cpp.

References work_q_t::mutex.

Referenced by task_main().

Here is the caller graph for this function:

◆ destroy_work_item()

static void destroy_work_item ( work_q_item_t item)
inlinestatic

Definition at line 357 of file dataman.cpp.

References work_q_item_t::link, lock_queue(), work_q_t::max_size, work_q_t::q, work_q_t::size, unlock_queue(), and work_q_item_t::wait_sem.

Referenced by enqueue_work_item_and_wait_for_result().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dm_clear()

__EXPORT int dm_clear ( dm_item_t  item)

Clear a data Item.

Erase all items of this type.

Definition at line 1135 of file dataman.cpp.

References work_q_item_t::clear_params, create_work_item(), dm_clear_func, enqueue_work_item_and_wait_for_result(), work_q_item_t::func, and is_running().

Referenced by Geofence::clearDm().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dm_lock()

__EXPORT int dm_lock ( dm_item_t  item)

Lock all items of a type.

Can be used for atomic updates of multiple items (single items are always updated atomically). Note that this lock is independent from dm_read & dm_write calls.

Returns
0 on success and lock taken, -1 on error (lock not taken, errno set)

Definition at line 1157 of file dataman.cpp.

References DM_KEY_NUM_KEYS, and is_running().

Referenced by MavlinkMissionManager::handle_mission_count(), MavlinkMissionManager::init_offboard_mission(), Mission::on_inactive(), Mission::reset_mission(), Mission::save_mission_state(), MavlinkMissionManager::update_active_mission(), and Geofence::updateFence().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dm_read()

__EXPORT ssize_t dm_read ( dm_item_t  item,
unsigned  index,
void *  buf,
size_t  count 
)

Retrieve from the data manager file.

Retrieve from the data manager store.

Definition at line 1104 of file dataman.cpp.

References _dm_read_perf, create_work_item(), dm_read_func, enqueue_work_item_and_wait_for_result(), work_q_item_t::func, is_running(), perf_begin(), perf_end(), and work_q_item_t::read_params.

Referenced by Geofence::_updateFence(), Mission::advance_mission(), MissionFeasibilityChecker::checkDistancesBetweenWaypoints(), MissionFeasibilityChecker::checkDistanceToFirstWaypoint(), MissionFeasibilityChecker::checkFixedWingLanding(), MissionFeasibilityChecker::checkGeofence(), MissionFeasibilityChecker::checkHomePositionAltitude(), MissionFeasibilityChecker::checkMissionItemValidity(), Geofence::checkPolygons(), MissionFeasibilityChecker::checkTakeoff(), RTL::find_RTL_destination(), Mission::index_closest_mission_item(), MavlinkMissionManager::init_offboard_mission(), Geofence::insideCircle(), Geofence::insidePolygon(), MavlinkMissionManager::load_geofence_stats(), MavlinkMissionManager::load_safepoint_stats(), Geofence::loadFromFile(), Commander::mission_init(), Mission::on_inactive(), Mission::read_mission_item(), Mission::reset_mission(), Mission::save_mission_state(), MavlinkMissionManager::send_mission_item(), task_main(), and test_dataman().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dm_restart()

__EXPORT int dm_restart ( dm_reset_reason  reason)

Tell the data manager about the type of the last reset.

Definition at line 1220 of file dataman.cpp.

References create_work_item(), dm_restart_func, enqueue_work_item_and_wait_for_result(), work_q_item_t::func, is_running(), and work_q_item_t::restart_params.

Referenced by dataman_main(), and test_dataman().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dm_trylock()

__EXPORT int dm_trylock ( dm_item_t  item)

Try to lock all items of a type (.

See also
sem_trywait()).
Returns
0 if lock is taken, -1 otherwise (on error or if already locked. errno is set accordingly)

Definition at line 1179 of file dataman.cpp.

References DM_KEY_NUM_KEYS, and is_running().

Referenced by Geofence::checkPolygons().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dm_unlock()

__EXPORT void dm_unlock ( dm_item_t  item)

Unlock a data Item.

Unlock all items of a type.

Definition at line 1202 of file dataman.cpp.

References DM_KEY_NUM_KEYS, and is_running().

Referenced by Geofence::checkPolygons(), MavlinkMissionManager::init_offboard_mission(), Mission::on_inactive(), Mission::reset_mission(), Mission::save_mission_state(), MavlinkMissionManager::switch_to_idle_state(), MavlinkMissionManager::update_active_mission(), and Geofence::updateFence().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dm_write()

__EXPORT ssize_t dm_write ( dm_item_t  item,
unsigned  index,
dm_persitence_t  persistence,
const void *  buf,
size_t  count 
)

Write to the data manager file.

write to the data manager store

Definition at line 1072 of file dataman.cpp.

References _dm_write_perf, create_work_item(), dm_write_func, enqueue_work_item_and_wait_for_result(), work_q_item_t::func, is_running(), perf_begin(), perf_end(), and work_q_item_t::write_params.

Referenced by MavlinkMissionManager::handle_mission_item_both(), Geofence::loadFromFile(), Commander::mission_init(), Mission::read_mission_item(), Mission::reset_mission(), Mission::save_mission_state(), task_main(), MavlinkMissionManager::update_active_mission(), MavlinkMissionManager::update_geofence_count(), and MavlinkMissionManager::update_safepoint_count().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ enqueue_work_item_and_wait_for_result()

static int enqueue_work_item_and_wait_for_result ( work_q_item_t item)
static

Definition at line 389 of file dataman.cpp.

References destroy_work_item(), work_q_item_t::link, lock_queue(), work_q_t::max_size, work_q_t::q, work_q_item_t::result, work_q_t::size, unlock_queue(), and work_q_item_t::wait_sem.

Referenced by dm_clear(), dm_read(), dm_restart(), and dm_write().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init_q()

static void init_q ( work_q_t q)
static

Definition at line 278 of file dataman.cpp.

References work_q_t::max_size, work_q_t::mutex, work_q_t::q, and work_q_t::size.

Referenced by task_main().

Here is the caller graph for this function:

◆ is_running()

◆ lock_queue()

static void lock_queue ( work_q_t q)
inlinestatic

Definition at line 292 of file dataman.cpp.

References work_q_t::mutex.

Referenced by create_work_item(), dequeue_work_item(), destroy_work_item(), and enqueue_work_item_and_wait_for_result().

Here is the caller graph for this function:

◆ start()

static int start ( )
static

Definition at line 1452 of file dataman.cpp.

References task_main(), and TASK_STACK_SIZE.

Referenced by land_detector::LandDetector::custom_command(), dataman_main(), do_level_calibration(), motor_ramp_thread_main(), uORB::Manager::node_open(), px4io_main(), px4::logger::LogWriterFile::run(), PX4IO::set_update_rate(), StraightLine::setLineFromTo(), DfLtc2946Wrapper::start(), DfBebopBusWrapper::start(), DfMS5607Wrapper::start(), DfBmp280Wrapper::start(), DfAK8963Wrapper::start(), DfBebopRangeFinderWrapper::start(), DfTROneWrapper::start(), DfISL29501Wrapper::start(), DfMPU6050Wrapper::start(), DfLsm9ds1Wrapper::start(), StraightLine::StraightLine(), test_file(), and write_test().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ status()

static void status ( )
static

Definition at line 1478 of file dataman.cpp.

References _dm_read_perf, _dm_write_perf, dm_clear_func, dm_read_func, dm_restart_func, dm_write_func, g_func_counts, work_q_t::max_size, and perf_print_counter().

Referenced by dataman_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ stop()

static void stop ( )
static

Definition at line 1491 of file dataman.cpp.

Referenced by dataman_main(), px4::bst::BST::ioctl(), DfLtc2946Wrapper::stop(), DfBebopBusWrapper::stop(), DfMS5607Wrapper::stop(), DfBmp280Wrapper::stop(), DfAK8963Wrapper::stop(), DfBebopRangeFinderWrapper::stop(), DfTROneWrapper::stop(), DfISL29501Wrapper::stop(), DfMPU6050Wrapper::stop(), and DfLsm9ds1Wrapper::stop().

Here is the caller graph for this function:

◆ task_main()

◆ unlock_queue()

static void unlock_queue ( work_q_t q)
inlinestatic

Definition at line 298 of file dataman.cpp.

References work_q_t::mutex.

Referenced by create_work_item(), dequeue_work_item(), destroy_work_item(), and enqueue_work_item_and_wait_for_result().

Here is the caller graph for this function:

◆ usage()

static void usage ( void  )
static

Definition at line 1499 of file dataman.cpp.

Referenced by backend_check(), and dataman_main().

Here is the caller graph for this function:

Variable Documentation

◆ _dm_read_perf

perf_counter_t _dm_read_perf {nullptr}
static

Definition at line 240 of file dataman.cpp.

Referenced by dm_read(), status(), and task_main().

◆ _dm_write_perf

perf_counter_t _dm_write_perf {nullptr}
static

Definition at line 241 of file dataman.cpp.

Referenced by dm_write(), status(), and task_main().

◆ backend

enum { ... } backend

◆ data

uint8_t* data

Definition at line 149 of file dataman.cpp.

Referenced by MavlinkFTP::__attribute__(), px4::Replay::CompatSensorCombinedDtType::apply(), PGA460::calc_checksum(), BMP280::collect(), BMP388::collect(), ComputeCRC16(), ADIS16497::crc32(), DShotTelemetry::decodeAndPrintEscInfoPacket(), OSDatxxxx::disable_screen(), OSDatxxxx::enable_screen(), uORB::KraitFastRpcChannel::fastrpc_recv_thread(), cdev::file_t::file_t(), fill_one_with_valid_data(), fill_two_with_valid_data(), MatrixTest::filterTests(), frsky_parse_host(), frsky_send_data(), EstimatorInterface::get_hagl_innov(), uORB::FastRpcChannel::GetInstance(), OSDatxxxx::init_osd(), BMM150::init_trim_registers(), MatrixTest::inverseTests(), uORB::KraitFastRpcChannel::isInstance(), main(), MatrixTest::matrixAssignmentTests(), MatrixTest::matrixMultTests(), MatrixTest::matrixScalarMultTests(), ICM20948_mag::measure(), MPU9250_mag::measure(), uORB::Manager::node_open(), px4::Replay::onSubscriptionAdded(), uORB::Manager::orb_advertise(), HMC5883_I2C::probe(), QMC5883_I2C::probe(), PMW3901::probe(), OSDatxxxx::probe(), IST8310::probe(), DataValidator::put(), linux_pwm_out::NavioSysfsPWMOut::pwm_write_sysfs(), PX4IO_serial_interface(), ICM20948_SPI::read(), MPU9250_SPI::read(), INA226::read(), PMW3901::readMotionCount(), PAW3902::registerWrite(), uORB::DeviceNode::remove_internal_subscriber(), PAW3902::Run(), ADC::sample(), linux_pwm_out::NavioSysfsPWMOut::send_output_pwm(), px4::bst::BST::send_packet(), PMW3901::sensorInit(), uORB::PublicationData< vehicle_global_position_s >::set(), uORB::PublicationMultiData< sensor_baro_s >::set(), EstimatorInterface::setAuxVelData(), EstimatorInterface::setBaroData(), EstimatorInterface::setMagData(), EstimatorInterface::setRangeData(), MatrixTest::sliceTests(), sPort_send_data(), MatrixTest::squareMatrixTests(), test_4x3(), test_4x4(), test_adc(), test_div_zero(), MPU6000::test_error(), test_jig_voltages(), test_priority_switch(), test_servo(), test_simple_failover(), MathlibTest::testVector2(), MathlibTest::testVector3(), timer_callback(), MatrixTest::transposeTests(), uORB::PublicationData< vehicle_global_position_s >::update(), uORB::PublicationMultiData< sensor_baro_s >::update(), MatrixTest::vector2Tests(), MatrixTest::vector3Tests(), INA226::write(), linux_pwm_out::PCA9685::write_byte(), OSDatxxxx::writeRegister(), PMW3901::writeRegister(), and TemperatureCalibrationGyro::~TemperatureCalibrationGyro().

◆ data_end

uint8_t* data_end

Definition at line 150 of file dataman.cpp.

◆ default_device_path

const char* default_device_path = PX4_STORAGEDIR "/dataman"
static

Definition at line 244 of file dataman.cpp.

◆ dm_file_operations

constexpr dm_operations_t dm_file_operations
static
Initial value:
= {
.write = _file_write,
.read = _file_read,
.clear = _file_clear,
.restart = _file_restart,
.initialize = _file_initialize,
.shutdown = _file_shutdown,
.wait = px4_sem_wait,
}
static ssize_t _file_read(dm_item_t item, unsigned index, void *buf, size_t count)
Definition: dataman.cpp:607
static ssize_t _file_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count)
Definition: dataman.cpp:490
static int _file_restart(dm_reset_reason reason)
Definition: dataman.cpp:803
static int _file_initialize(unsigned max_offset)
Definition: dataman.cpp:883
static void _file_shutdown()
Definition: dataman.cpp:997
static int _file_clear(dm_item_t item)
Definition: dataman.cpp:698

Definition at line 109 of file dataman.cpp.

Referenced by task_main().

◆ dm_operations_data

◆ dm_ram_operations

constexpr dm_operations_t dm_ram_operations
static
Initial value:
= {
.write = _ram_write,
.read = _ram_read,
.clear = _ram_clear,
.restart = _ram_restart,
.initialize = _ram_initialize,
.shutdown = _ram_shutdown,
.wait = px4_sem_wait,
}
static ssize_t _ram_read(dm_item_t item, unsigned index, void *buf, size_t count)
Definition: dataman.cpp:567
static ssize_t _ram_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count)
Definition: dataman.cpp:451
static int _ram_restart(dm_reset_reason reason)
Definition: dataman.cpp:763
static void _ram_shutdown()
Definition: dataman.cpp:1004
static int _ram_initialize(unsigned max_offset)
Definition: dataman.cpp:940
static int _ram_clear(dm_item_t item)
Definition: dataman.cpp:668

Definition at line 119 of file dataman.cpp.

Referenced by _file_clear(), _file_read(), _file_restart(), _file_write(), _ram_initialize(), _ram_shutdown(), and task_main().

◆ fd

int fd

Definition at line 146 of file dataman.cpp.

Referenced by MavlinkFtpTest::_burst_test(), MavlinkFtpTest::_read_test(), MavlinkFtpTest::_removedirectory_test(), MavlinkFtpTest::_removefile_test(), MavlinkFTP::_workCalcFileCRC32(), MavlinkFTP::_workOpen(), MavlinkFTP::_workTruncateFile(), VtolType::apply_pwm_limits(), bl_update_main(), blinkm_main(), bson_decoder_init_file(), bson_encoder_init_buf_file(), bson_encoder_init_file(), calc_timer_diff_to_dsp_us(), lis3mdl::calibrate(), HMC5883::calibrate(), LIS3MDL::calibrate(), hmc5883::calibrate(), IST8310::calibrate(), ist8310::calibrate(), LidarLitePWM::collect(), do_accel(), do_accel_calibration(), do_airspeed_calibration(), do_device(), do_esc_calibration(), do_gyro(), do_gyro_calibration(), do_import(), do_load(), do_mag(), do_mag_calibration(), CDevExample::do_poll(), do_save(), esc_calib_main(), ParameterTest::exportImportAll(), LinuxGPIO::exportPin(), get_vdev(), MavlinkReceiver::handle_message_play_tune(), hardfault_append_to_ulog(), hardfault_check_status(), hardfault_commit(), hardfault_get_desc(), hardfault_increment_reboot(), px4::logger::LogWriterFile::hardfault_store_filename(), rm3100::init(), lis3mdl::init(), VtolType::init(), CDevExample::main(), motor_ramp_thread_main(), mtd_main(), uORB::Manager::node_open(), nshterm_main(), linux_pwm_out::PCA9685::open_fd(), uORB::Manager::orb_advertise_multi(), uORB::Manager::orb_exists(), param_save_default(), Sensors::parameter_update_poll(), pca9685_main(), pwm_main(), linux_pwm_out::NavioSysfsPWMOut::pwm_write_sysfs(), pwmin_reset(), pwmin_test(), px4_close(), px4_poll(), uORB::SubscriptionCallback::registerCallback(), Mavlink::request_stop_ulog_streaming(), ms5525_airspeed::reset(), sdp3x_airspeed::reset(), pmw3901::reset(), bmm150::reset(), lps22hb::reset(), rm3100::reset(), lis3mdl::reset(), meas_airspeed::reset(), srf02::reset(), sf1xx::reset(), mpl3115a2::reset(), sf0x::reset(), lps25h::reset(), bma180::reset(), qmc5883::reset(), ist8310::reset(), px4::logger::LogWriterFile::run(), MavlinkReceiver::Run(), ADC::sample(), CameraCapture::set_capture_control(), PX4IO::set_update_rate(), LinuxGPIO::setDirection(), bmm150::start(), sf0x::start(), bma180::start(), ms5525_airspeed::start_bus(), sdp3x_airspeed::start_bus(), lps22hb::start_bus(), hmc5883::start_bus(), ms5611::start_bus(), ets_airspeed::start_bus(), meas_airspeed::start_bus(), srf02::start_bus(), sf1xx::start_bus(), mpl3115a2::start_bus(), lps25h::start_bus(), qmc5883::start_bus(), ist8310::start_bus(), px4::logger::LogWriterFile::start_log(), rc_receiver::task_main(), hmc5883::temp_enable(), pmw3901::test(), bmm150::test(), rm3100::test(), lis3mdl::test(), PX4FMU::test(), radar::test(), leddar_one::test(), srf02::test(), sf1xx::test(), mpl3115a2::test(), sf0x::test(), lps25h::test(), bma180::test(), vl53lxx::test(), qmc5883::test(), ist8310::test(), test_adc(), test_corruption(), test_file(), test_hott_telemetry(), test_jig_voltages(), test_led(), test_mount(), test_servo(), LinuxGPIO::unexportPin(), and writer_main().

◆ file

◆ g_dm_ops

const dm_operations_t* g_dm_ops
static

Definition at line 141 of file dataman.cpp.

◆ g_free_q

work_q_t g_free_q
static

Definition at line 270 of file dataman.cpp.

◆ g_func_counts

unsigned g_func_counts[dm_number_of_funcs]
static

Definition at line 206 of file dataman.cpp.

Referenced by status(), and task_main().

◆ g_init_sema

px4_sem_t g_init_sema
static

Definition at line 274 of file dataman.cpp.

◆ g_item_locks

px4_sem_t* g_item_locks[DM_KEY_NUM_KEYS]
static

Definition at line 236 of file dataman.cpp.

◆ g_key_offsets

unsigned int g_key_offsets[DM_KEY_NUM_KEYS]
static

Definition at line 233 of file dataman.cpp.

◆ g_per_item_max_index

◆ g_per_item_size

constexpr size_t g_per_item_size[DM_KEY_NUM_KEYS]
static
Initial value:
= {
sizeof(struct mission_s) + DM_SECTOR_HDR_SIZE,
}
Global position setpoint in WGS84 coordinates.
Definition: navigation.h:145
#define DM_SECTOR_HDR_SIZE
Definition: dataman.cpp:219
Geofence vertex point.
Definition: navigation.h:203
Safe Point (Rally Point).
Definition: navigation.h:223

Definition at line 222 of file dataman.cpp.

Referenced by _file_clear(), _file_read(), _file_restart(), _file_write(), _ram_clear(), _ram_read(), _ram_restart(), _ram_write(), calculate_offset(), and task_main().

◆ g_sys_state_mutex_fence

px4_sem_t g_sys_state_mutex_fence
static

Definition at line 238 of file dataman.cpp.

Referenced by task_main().

◆ g_sys_state_mutex_mission

px4_sem_t g_sys_state_mutex_mission
static

Definition at line 237 of file dataman.cpp.

Referenced by task_main().

◆ g_task_should_exit

bool g_task_should_exit
static

if true, dataman task should exit

Definition at line 276 of file dataman.cpp.

◆ g_work_q

work_q_t g_work_q
static

Definition at line 271 of file dataman.cpp.

◆ g_work_queued_sema

px4_sem_t g_work_queued_sema
static

Definition at line 273 of file dataman.cpp.

◆ k_data_manager_device_path

char* k_data_manager_device_path = nullptr
static

Definition at line 245 of file dataman.cpp.

◆ k_work_item_allocation_chunk_size

const size_t k_work_item_allocation_chunk_size = 8

Definition at line 203 of file dataman.cpp.

Referenced by create_work_item().

◆ ram

struct { ... } ram

◆ running

bool running

Definition at line 161 of file dataman.cpp.

◆ TASK_STACK_SIZE

__END_DECLS constexpr int TASK_STACK_SIZE = 1220
static

Definition at line 65 of file dataman.cpp.

Referenced by start().