PX4 Firmware
PX4 Autopilot Software http://px4.io
|
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"
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_t * | create_work_item () |
static void | destroy_work_item (work_q_item_t *item) |
static work_q_item_t * | dequeue_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 () |
DATAMANAGER driver.
Definition in file dataman.cpp.
#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 struct dm_operations_t dm_operations_t |
anonymous enum |
Enumerator | |
---|---|
BACKEND_NONE | |
BACKEND_FILE | |
BACKEND_RAM | |
BACKEND_LAST |
Definition at line 251 of file dataman.cpp.
enum 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.
|
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.
|
static |
Definition at line 883 of file dataman.cpp.
References DM_COMPAT_KEY, DM_KEY_COMPAT, dm_operations_data, DM_PERSIST_POWER_ON_RESET, dataman_compat_s::key, dm_operations_t::read, and dm_operations_t::write.
|
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.
|
static |
Definition at line 803 of file dataman.cpp.
References DM_INIT_REASON_POWER_ON, DM_KEY_NUM_KEYS, DM_KEY_SAFE_POINTS, dm_operations_data, DM_PERSIST_IN_FLIGHT_RESET, DM_PERSIST_POWER_ON_RESET, dm_ram_operations, g_per_item_max_index, g_per_item_size, dm_operations_t::read, dm_operations_t::restart, and dm_operations_t::write.
|
static |
Definition at line 997 of file dataman.cpp.
References dm_operations_data.
|
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.
|
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.
|
static |
Definition at line 940 of file dataman.cpp.
References DM_COMPAT_KEY, DM_KEY_COMPAT, dm_operations_data, DM_PERSIST_POWER_ON_RESET, dm_ram_operations, dm_operations_t::initialize, dataman_compat_s::key, dm_operations_t::read, and dm_operations_t::write.
|
static |
Definition at line 567 of file dataman.cpp.
References calculate_offset(), dm_operations_data, and g_per_item_size.
|
static |
Definition at line 763 of file dataman.cpp.
References DM_INIT_REASON_POWER_ON, DM_KEY_NUM_KEYS, DM_KEY_SAFE_POINTS, dm_operations_data, DM_PERSIST_IN_FLIGHT_RESET, DM_PERSIST_POWER_ON_RESET, g_per_item_max_index, and g_per_item_size.
|
static |
Definition at line 1004 of file dataman.cpp.
References dm_operations_data, dm_ram_operations, and dm_operations_t::shutdown.
|
static |
Definition at line 451 of file dataman.cpp.
References calculate_offset(), dm_operations_data, and g_per_item_size.
|
static |
Definition at line 1537 of file dataman.cpp.
References BACKEND_NONE, and usage().
Referenced by dataman_main().
|
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().
|
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().
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().
|
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().
|
inlinestatic |
Definition at line 286 of file dataman.cpp.
References work_q_t::mutex.
Referenced by task_main().
|
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().
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().
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.
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().
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().
__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().
Try to lock all items of a type (.
Definition at line 1179 of file dataman.cpp.
References DM_KEY_NUM_KEYS, and is_running().
Referenced by Geofence::checkPolygons().
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().
__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().
|
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().
|
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().
|
static |
Definition at line 415 of file dataman.cpp.
References dm_operations_data.
Referenced by events::SendEvent::custom_command(), RCInput::custom_command(), Heater::custom_command(), AirspeedModule::custom_command(), Navigator::custom_command(), GPS::custom_command(), px4::logger::Logger::custom_command(), DShotOutput::custom_command(), PX4FMU::custom_command(), BATT_SMBUS::custom_command(), dataman_main(), dm_clear(), dm_lock(), dm_read(), dm_restart(), dm_trylock(), dm_unlock(), dm_write(), PX4FMU::fmu_new_mode(), DShotOutput::module_new_mode(), px4::logger::Logger::request_stop_static(), events::SendEvent::start(), and BATT_SMBUS::task_spawn().
|
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().
|
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().
|
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().
|
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().
|
static |
Definition at line 1251 of file dataman.cpp.
References _dm_read_perf, _dm_write_perf, BACKEND_FILE, BACKEND_NONE, BACKEND_RAM, dm_operations_t::clear, work_q_item_t::clear_params, dequeue_work_item(), destroy_q(), dm_clear_func, dm_file_operations, DM_INIT_REASON_IN_FLIGHT, DM_INIT_REASON_POWER_ON, DM_KEY_FENCE_POINTS, DM_KEY_MISSION_STATE, DM_KEY_NUM_KEYS, dm_number_of_funcs, dm_ram_operations, dm_read_func, dm_restart_func, dm_write_func, work_q_item_t::first, work_q_item_t::func, g_func_counts, g_per_item_max_index, g_per_item_size, g_sys_state_mutex_fence, g_sys_state_mutex_mission, init_q(), dm_operations_t::initialize, OK, param_find(), param_get(), PC_ELAPSED, perf_alloc, perf_free(), work_q_t::q, dm_operations_t::read, work_q_item_t::read_params, dm_operations_t::restart, work_q_item_t::restart_params, work_q_item_t::result, dm_operations_t::shutdown, dm_operations_t::wait, work_q_item_t::wait_sem, dm_operations_t::write, and work_q_item_t::write_params.
Referenced by start().
|
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().
|
static |
Definition at line 1499 of file dataman.cpp.
Referenced by backend_check(), and dataman_main().
|
static |
Definition at line 240 of file dataman.cpp.
Referenced by dm_read(), status(), and task_main().
|
static |
Definition at line 241 of file dataman.cpp.
Referenced by dm_write(), status(), and task_main().
enum { ... } backend |
Referenced by px4::logger::Logger::instantiate().
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().
uint8_t* data_end |
Definition at line 150 of file dataman.cpp.
|
static |
Definition at line 244 of file dataman.cpp.
|
static |
Definition at line 109 of file dataman.cpp.
Referenced by task_main().
struct { ... } dm_operations_data |
|
static |
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().
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().
struct { ... } file |
Referenced by MavlinkFtpTest::_read_badsession_test(), MavlinkFtpTest::_removefile_test(), MavlinkFtpTest::_terminate_badsession_test(), LogListHelper::get_entry(), UavcanMagnetometerBridge::get_name(), px4::Replay::onSubscriptionAdded(), UavcanNode::run(), Mavlink2Dev::~Mavlink2Dev(), and RtpsDev::~RtpsDev().
|
static |
Definition at line 141 of file dataman.cpp.
|
static |
Definition at line 270 of file dataman.cpp.
|
static |
Definition at line 206 of file dataman.cpp.
Referenced by status(), and task_main().
|
static |
Definition at line 274 of file dataman.cpp.
|
static |
Definition at line 236 of file dataman.cpp.
|
static |
Definition at line 233 of file dataman.cpp.
|
static |
Definition at line 209 of file dataman.cpp.
Referenced by _file_clear(), _file_restart(), _ram_clear(), _ram_restart(), calculate_offset(), and task_main().
|
static |
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().
|
static |
Definition at line 238 of file dataman.cpp.
Referenced by task_main().
|
static |
Definition at line 237 of file dataman.cpp.
Referenced by task_main().
|
static |
if true, dataman task should exit
Definition at line 276 of file dataman.cpp.
|
static |
Definition at line 271 of file dataman.cpp.
|
static |
Definition at line 273 of file dataman.cpp.
|
static |
Definition at line 245 of file dataman.cpp.
const size_t k_work_item_allocation_chunk_size = 8 |
Definition at line 203 of file dataman.cpp.
Referenced by create_work_item().
struct { ... } ram |
bool running |
Definition at line 161 of file dataman.cpp.
|
static |
Definition at line 65 of file dataman.cpp.
Referenced by start().