PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include "cdev_platform.hpp"
#include <string>
#include <map>
#include "vfile.h"
#include "../CDev.hpp"
#include <px4_platform_common/log.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/time.h>
#include "DevMgr.hpp"
Go to the source code of this file.
Macros | |
#define | PX4_MAX_FD 350 |
Functions | |
static cdev::CDev * | getDev (const char *path) |
static cdev::CDev * | get_vdev (int fd) |
int | register_driver (const char *name, const cdev::px4_file_operations_t *fops, cdev::mode_t mode, void *data) |
int | unregister_driver (const char *name) |
int | px4_open (const char *path, int flags,...) |
int | px4_close (int fd) |
ssize_t | px4_read (int fd, void *buffer, size_t buflen) |
ssize_t | px4_write (int fd, const void *buffer, size_t buflen) |
int | px4_ioctl (int fd, int cmd, unsigned long arg) |
int | px4_poll (px4_pollfd_struct_t *fds, nfds_t nfds, int timeout) |
int | px4_fsync (int fd) |
int | px4_access (const char *pathname, int mode) |
void | px4_show_devices () |
void | px4_show_topics () |
void | px4_show_files () |
Variables | |
pthread_mutex_t | devmutex = PTHREAD_MUTEX_INITIALIZER |
pthread_mutex_t | filemutex = PTHREAD_MUTEX_INITIALIZER |
static map< string, void * > | devmap |
static cdev::file_t | filemap [PX4_MAX_FD] = {} |
int | px4_errno |
#define PX4_MAX_FD 350 |
Definition at line 57 of file cdev_platform.cpp.
Referenced by px4_open().
|
static |
Definition at line 83 of file cdev_platform.cpp.
References fd, filemutex, and cdev::file_t::vdev.
Referenced by px4_close(), px4_ioctl(), px4_poll(), px4_read(), and px4_write().
|
static |
Definition at line 65 of file cdev_platform.cpp.
References devmutex.
Referenced by px4_access(), and px4_open().
int px4_access | ( | const char * | pathname, |
int | mode | ||
) |
Definition at line 429 of file cdev_platform.cpp.
References getDev().
Referenced by uORB::Manager::orb_exists().
int px4_close | ( | int | fd | ) |
Definition at line 216 of file cdev_platform.cpp.
References cdev::CDev::close(), fd, filemutex, get_vdev(), and cdev::file_t::vdev.
Referenced by VtolType::apply_pwm_limits(), blinkm_main(), hmc5883::calibrate(), calibrate_from_orientation(), PGA460::close_serial(), commander_low_prio_loop(), do_accel_calibration(), do_accel_calibration_measurements(), do_airspeed_calibration(), do_esc_calibration(), do_gyro_calibration(), do_mag_calibration(), MavlinkReceiver::handle_message_play_tune(), VtolType::init(), mag_calibrate_all(), mag_calibration_worker(), CDevExample::main(), motor_ramp_thread_main(), uORB::Manager::orb_advertise_multi(), uORB::Manager::orb_exists(), uORB::Manager::orb_unsubscribe(), Sensors::parameter_update_poll(), srf02::reset(), sf1xx::reset(), lsm303agr::start(), lps22hb::start_bus(), hmc5883::start_bus(), ms5611::start_bus(), srf02::start_bus(), sf1xx::start_bus(), hmc5883::temp_enable(), sf1xx::test(), vl53lxx::test(), test_adc(), test_file(), test_mount(), and writer_main().
int px4_fsync | ( | int | fd | ) |
Definition at line 424 of file cdev_platform.cpp.
int px4_ioctl | ( | int | fd, |
int | cmd, | ||
unsigned long | arg | ||
) |
Definition at line 287 of file cdev_platform.cpp.
References get_vdev(), and cdev::CDev::ioctl().
Referenced by VtolType::apply_pwm_limits(), blinkm_main(), HMC5883::calibrate(), hmc5883::calibrate(), do_accel_calibration(), do_airspeed_calibration(), do_esc_calibration(), do_gyro_calibration(), do_mag_calibration(), VtolType::init(), load(), mag_calibrate_all(), motor_ramp_thread_main(), uORB::Manager::orb_advertise_multi(), uORB::Manager::orb_check(), uORB::Manager::orb_exists(), uORB::Manager::orb_get_interval(), uORB::Manager::orb_priority(), uORB::Manager::orb_set_interval(), uORB::Manager::orb_stat(), Sensors::parameter_update_poll(), prepare(), pwm_main(), ms5525_airspeed::reset(), sdp3x_airspeed::reset(), pmw3901::reset(), lps22hb::reset(), meas_airspeed::reset(), set_min_pwm(), lsm303agr::start(), ms5525_airspeed::start_bus(), sdp3x_airspeed::start_bus(), lps22hb::start_bus(), hmc5883::start_bus(), ets_airspeed::start_bus(), meas_airspeed::start_bus(), hmc5883::temp_enable(), and test_led().
int px4_open | ( | const char * | path, |
int | flags, | ||
... | |||
) |
Definition at line 148 of file cdev_platform.cpp.
References cdev::VFile::createFile(), filemutex, getDev(), cdev::CDev::open(), and PX4_MAX_FD.
Referenced by VtolType::apply_pwm_limits(), blinkm_main(), hmc5883::calibrate(), do_accel_calibration(), do_airspeed_calibration(), do_esc_calibration(), do_gyro_calibration(), do_mag_calibration(), MavlinkReceiver::handle_message_play_tune(), VtolType::init(), load(), mag_calibrate_all(), CDevExample::main(), motor_ramp_thread_main(), uORB::Manager::node_open(), PGA460::open_serial(), uORB::Manager::orb_exists(), Sensors::parameter_update_poll(), pwm_main(), sdp3x_airspeed::reset(), ms5525_airspeed::reset(), pmw3901::reset(), meas_airspeed::reset(), srf02::reset(), sf1xx::reset(), lsm303agr::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(), hmc5883::temp_enable(), pmw3901::test(), srf02::test(), sf1xx::test(), vl53lxx::test(), test_adc(), test_file(), test_led(), test_mount(), and writer_main().
int px4_poll | ( | px4_pollfd_struct_t * | fds, |
nfds_t | nfds, | ||
int | timeout | ||
) |
Definition at line 308 of file cdev_platform.cpp.
References fd, get_vdev(), and cdev::CDev::poll().
Referenced by HMC5883::calibrate(), calibrate_cancel_check(), commander_low_prio_loop(), TAP_ESC::cycle(), detect_orientation(), do_airspeed_calibration(), do_level_calibration(), CDevExample::do_poll(), gyro_calibration_worker(), px4::ReplayEkf2::handleTopicUpdate(), mag_calibration_worker(), QShell::main(), px4::logger::LogWriterMavlink::publish_message(), uORBTest::UnitTest::pubsublatency_main(), read_accelerometer_avg(), RoverPositionControl::run(), Sensors::run(), Navigator::run(), px4::logger::Logger::run(), Simulator::send(), TemperatureCalibration::task_main(), CameraFeedback::task_main(), uart_esc::task_main(), linux_pwm_out::task_main(), snapdragon_pwm::task_main(), df_bebop_bus_wrapper::task_main(), uORBTest::UnitTest::test_queue_poll_notify(), vmount::InputMavlinkROI::update_impl(), vmount::InputRC::update_impl(), and vmount::InputMavlinkCmdMount::update_impl().
ssize_t px4_read | ( | int | fd, |
void * | buffer, | ||
size_t | buflen | ||
) |
Definition at line 243 of file cdev_platform.cpp.
References get_vdev(), and cdev::CDev::read().
Referenced by HMC5883::calibrate(), CDevExample::do_poll(), uORB::Manager::orb_copy(), and test_adc().
void px4_show_devices | ( | ) |
Definition at line 440 of file cdev_platform.cpp.
References devmutex.
void px4_show_files | ( | ) |
Definition at line 485 of file cdev_platform.cpp.
References devmutex.
void px4_show_topics | ( | ) |
Definition at line 470 of file cdev_platform.cpp.
References devmutex.
ssize_t px4_write | ( | int | fd, |
const void * | buffer, | ||
size_t | buflen | ||
) |
Definition at line 265 of file cdev_platform.cpp.
References get_vdev(), and cdev::CDev::write().
Referenced by MavlinkReceiver::handle_message_play_tune(), and writer_main().
int register_driver | ( | const char * | name, |
const cdev::px4_file_operations_t * | fops, | ||
cdev::mode_t | mode, | ||
void * | data | ||
) |
Definition at line 100 of file cdev_platform.cpp.
References devmutex, and name.
Referenced by cdev::VFile::createFile(), cdev::file_t::file_t(), cdev::CDev::init(), MK::init(), PX4IO::init(), and cdev::CDev::register_class_devname().
int unregister_driver | ( | const char * | name | ) |
Definition at line 127 of file cdev_platform.cpp.
References devmutex.
Referenced by cdev::file_t::file_t(), PX4IO::task_main(), cdev::CDev::unregister_class_devname(), cdev::CDev::unregister_driver_and_memory(), cdev::CDev::~CDev(), and MK::~MK().
|
static |
Definition at line 58 of file cdev_platform.cpp.
pthread_mutex_t devmutex = PTHREAD_MUTEX_INITIALIZER |
Definition at line 54 of file cdev_platform.cpp.
Referenced by getDev(), px4_show_devices(), px4_show_files(), px4_show_topics(), register_driver(), and unregister_driver().
|
static |
Definition at line 59 of file cdev_platform.cpp.
pthread_mutex_t filemutex = PTHREAD_MUTEX_INITIALIZER |
Definition at line 55 of file cdev_platform.cpp.
Referenced by get_vdev(), px4_close(), and px4_open().
int px4_errno |
Definition at line 63 of file cdev_platform.cpp.