PX4 Firmware
PX4 Autopilot Software http://px4.io
|
DATAMANAGER driver. More...
Go to the source code of this file.
Classes | |
struct | dataman_compat_s |
Macros | |
#define | DM_COMPAT_VERSION 2ULL |
#define | DM_COMPAT_KEY |
Enumerations | |
enum | dm_item_t { DM_KEY_SAFE_POINTS = 0, DM_KEY_FENCE_POINTS, DM_KEY_WAYPOINTS_OFFBOARD_0, DM_KEY_WAYPOINTS_OFFBOARD_1, DM_KEY_WAYPOINTS_ONBOARD, DM_KEY_MISSION_STATE, DM_KEY_COMPAT, DM_KEY_NUM_KEYS } |
Types of items that the data manager can store. More... | |
enum | { DM_KEY_SAFE_POINTS_MAX = 8, DM_KEY_FENCE_POINTS_MAX = 64, DM_KEY_WAYPOINTS_OFFBOARD_0_MAX = NUM_MISSIONS_SUPPORTED, DM_KEY_WAYPOINTS_OFFBOARD_1_MAX = NUM_MISSIONS_SUPPORTED, DM_KEY_WAYPOINTS_ONBOARD_MAX = NUM_MISSIONS_SUPPORTED, DM_KEY_MISSION_STATE_MAX = 1, DM_KEY_COMPAT_MAX = 1 } |
The maximum number of instances for each item type. More... | |
enum | dm_persitence_t { DM_PERSIST_POWER_ON_RESET = 0, DM_PERSIST_IN_FLIGHT_RESET, DM_PERSIST_VOLATILE } |
Data persistence levels. More... | |
enum | dm_reset_reason { DM_INIT_REASON_POWER_ON = 0, DM_INIT_REASON_IN_FLIGHT, DM_INIT_REASON_VOLATILE } |
The reason for the last reset. More... | |
Functions | |
__EXPORT ssize_t | dm_read (dm_item_t item, unsigned index, void *buffer, size_t buflen) |
Retrieve from the data manager store. More... | |
__EXPORT ssize_t | dm_write (dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buffer, size_t buflen) |
write to the data manager store 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 all items of a type. More... | |
__EXPORT int | dm_clear (dm_item_t item) |
Erase all items of this type. More... | |
__EXPORT int | dm_restart (dm_reset_reason restart_type) |
Tell the data manager about the type of the last reset. More... | |
DATAMANAGER driver.
Definition in file dataman.h.
#define DM_COMPAT_KEY |
Definition at line 104 of file dataman.h.
Referenced by _file_initialize(), and _ram_initialize().
anonymous enum |
enum dm_item_t |
enum dm_persitence_t |
enum dm_reset_reason |
Erase all items of this type.
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 store.
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 | restart_type | ) |
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 all items of a type.
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 store
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().