PX4 Firmware
PX4 Autopilot Software http://px4.io
UavcanMagnetometerBridge Class Reference

#include <mag.hpp>

Inheritance diagram for UavcanMagnetometerBridge:
Collaboration diagram for UavcanMagnetometerBridge:

Public Member Functions

 UavcanMagnetometerBridge (uavcan::INode &node)
 
const char * get_name () const override
 Returns ASCII name of the bridge. More...
 
int init () override
 Starts the bridge. More...
 
- Public Member Functions inherited from UavcanCDevSensorBridgeBase
virtual ~UavcanCDevSensorBridgeBase ()
 
unsigned get_num_redundant_channels () const override
 Returns number of active redundancy channels. More...
 
void print_status () const override
 Prints current status in a human readable format to stdout. More...
 
- Public Member Functions inherited from IUavcanSensorBridge
virtual ~IUavcanSensorBridge ()=default
 
- Public Member Functions inherited from ListNode< IUavcanSensorBridge *>
void setSibling (IUavcanSensorBridge * sibling)
 
const IUavcanSensorBridgegetSibling () const
 
- Public Member Functions inherited from device::CDev
 CDev (const char *name, const char *devname)
 Constructor. More...
 
virtual ~CDev ()=default
 
virtual int ioctl (file_t *filep, int cmd, unsigned long arg)
 Perform an ioctl operation on the device. More...
 
- Public Member Functions inherited from device::Device
 Device (const Device &)=delete
 
Deviceoperator= (const Device &)=delete
 
 Device (Device &&)=delete
 
Deviceoperator= (Device &&)=delete
 
virtual ~Device ()=default
 Destructor. More...
 
virtual int read (unsigned address, void *data, unsigned count)
 Read directly from the device. More...
 
virtual int write (unsigned address, void *data, unsigned count)
 Write directly to the device. More...
 
virtual int ioctl (unsigned operation, unsigned &arg)
 Perform a device-specific operation. More...
 
uint32_t get_device_id () const
 
DeviceBusType get_device_bus_type () const
 Return the bus type the device is connected to. More...
 
void set_device_bus_type (DeviceBusType bus_type)
 
uint8_t get_device_bus () const
 Return the bus ID the device is connected to. More...
 
void set_device_bus (uint8_t bus)
 
uint8_t get_device_address () const
 Return the bus address of the device. More...
 
void set_device_address (int address)
 
uint8_t get_device_type () const
 Return the device type. More...
 
void set_device_type (uint8_t devtype)
 
virtual bool external () const
 
- Public Member Functions inherited from cdev::CDev
 CDev (const char *devname)
 Constructor. More...
 
 CDev (const CDev &)=delete
 
CDevoperator= (const CDev &)=delete
 
 CDev (CDev &&)=delete
 
CDevoperator= (CDev &&)=delete
 
virtual int open (file_t *filep)
 Handle an open of the device. More...
 
virtual int close (file_t *filep)
 Handle a close of the device. More...
 
virtual ssize_t read (file_t *filep, char *buffer, size_t buflen)
 Perform a read from the device. More...
 
virtual ssize_t write (file_t *filep, const char *buffer, size_t buflen)
 Perform a write to the device. More...
 
virtual off_t seek (file_t *filep, off_t offset, int whence)
 Perform a logical seek operation on the device. More...
 
virtual int poll (file_t *filep, px4_pollfd_struct_t *fds, bool setup)
 Perform a poll setup/teardown operation. More...
 
const char * get_devname () const
 Get the device name. More...
 

Static Public Attributes

static const char *const NAME = "mag"
 
- Static Public Attributes inherited from IUavcanSensorBridge
static constexpr unsigned MAX_NAME_LEN = 20
 

Private Types

typedef uavcan::MethodBinder< UavcanMagnetometerBridge *, void(UavcanMagnetometerBridge::*)(const uavcan::ReceivedDataStructure< uavcan::equipment::ahrs::MagneticFieldStrength > &) > MagCbBinder
 
typedef uavcan::MethodBinder< UavcanMagnetometerBridge *, void(UavcanMagnetometerBridge::*)(const uavcan::ReceivedDataStructure< uavcan::equipment::ahrs::MagneticFieldStrength2 > &) > Mag2CbBinder
 

Private Member Functions

int ioctl (struct file *filp, int cmd, unsigned long arg) override
 
void mag_sub_cb (const uavcan::ReceivedDataStructure< uavcan::equipment::ahrs::MagneticFieldStrength > &msg)
 
void mag2_sub_cb (const uavcan::ReceivedDataStructure< uavcan::equipment::ahrs::MagneticFieldStrength2 > &msg)
 

Private Attributes

uavcan::Subscriber< uavcan::equipment::ahrs::MagneticFieldStrength, MagCbBinder_sub_mag
 
uavcan::Subscriber< uavcan::equipment::ahrs::MagneticFieldStrength2, Mag2CbBinder_sub_mag2
 
mag_calibration_s _scale {}
 
sensor_mag_s _report {}
 

Additional Inherited Members

- Public Types inherited from device::Device
enum  DeviceBusType {
  DeviceBusType_UNKNOWN = 0, DeviceBusType_I2C = 1, DeviceBusType_SPI = 2, DeviceBusType_UAVCAN = 3,
  DeviceBusType_SIMULATION = 4
}
 Device bus types for DEVID. More...
 
- Static Public Member Functions inherited from IUavcanSensorBridge
static void make_all (uavcan::INode &node, List< IUavcanSensorBridge *> &list)
 Sensor bridge factory. More...
 
- Static Public Member Functions inherited from device::Device
static const char * get_device_bus_string (DeviceBusType bus)
 
static int device_id_print_buffer (char *buffer, int length, uint32_t id)
 Print decoded device id string to a buffer. More...
 
- Protected Member Functions inherited from UavcanCDevSensorBridgeBase
 UavcanCDevSensorBridgeBase (const char *name, const char *devname, const char *class_devname, const orb_id_t orb_topic_sensor, const unsigned max_channels=DEFAULT_MAX_CHANNELS)
 
void publish (const int node_id, const void *report)
 Sends one measurement into appropriate ORB topic. More...
 
- Protected Member Functions inherited from device::Device
 Device (const char *name)
 
 Device (const char *name, DeviceBusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype=0)
 
 Device (DeviceBusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype=0)
 
- Protected Member Functions inherited from cdev::CDev
virtual pollevent_t poll_state (file_t *filep)
 Check the current state of the device for poll events from the perspective of the file. More...
 
virtual void poll_notify (pollevent_t events)
 Report new poll events. More...
 
virtual void poll_notify_one (px4_pollfd_struct_t *fds, pollevent_t events)
 Internal implementation of poll_notify. More...
 
virtual int open_first (file_t *filep)
 Notification of the first open. More...
 
virtual int close_last (file_t *filep)
 Notification of the last close. More...
 
virtual int register_class_devname (const char *class_devname)
 Register a class device name, automatically adding device class instance suffix if need be. More...
 
virtual int unregister_class_devname (const char *class_devname, unsigned class_instance)
 Register a class device name, automatically adding device class instance suffix if need be. More...
 
void lock ()
 Take the driver lock. More...
 
void unlock ()
 Release the driver lock. More...
 
int unregister_driver_and_memory ()
 First, unregisters the driver. More...
 
- Protected Attributes inherited from ListNode< IUavcanSensorBridge *>
IUavcanSensorBridge_list_node_sibling
 
- Protected Attributes inherited from device::CDev
bool _pub_blocked {false}
 true if publishing should be blocked More...
 
- Protected Attributes inherited from device::Device
const char * _name {nullptr}
 driver name More...
 
bool _debug_enabled {false}
 if true, debug messages are printed More...
 
- Protected Attributes inherited from cdev::CDev
px4_sem_t _lock
 lock to protect access to all class members (also for derived classes) More...
 
- Static Protected Attributes inherited from UavcanCDevSensorBridgeBase
static constexpr unsigned DEFAULT_MAX_CHANNELS = 5
 
- Static Protected Attributes inherited from cdev::CDev
static const px4_file_operations_t fops = {}
 Pointer to the default cdev file operations table; useful for registering clone devices etc. More...
 

Detailed Description

Author
Pavel Kirienko pavel.nosp@m..kir.nosp@m.ienko.nosp@m.@gma.nosp@m.il.co.nosp@m.m

Definition at line 47 of file mag.hpp.

Member Typedef Documentation

◆ Mag2CbBinder

typedef uavcan::MethodBinder< UavcanMagnetometerBridge *, void (UavcanMagnetometerBridge::*) (const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::MagneticFieldStrength2> &) > UavcanMagnetometerBridge::Mag2CbBinder
private

Definition at line 73 of file mag.hpp.

◆ MagCbBinder

typedef uavcan::MethodBinder< UavcanMagnetometerBridge *, void (UavcanMagnetometerBridge::*) (const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::MagneticFieldStrength> &) > UavcanMagnetometerBridge::MagCbBinder
private

Definition at line 68 of file mag.hpp.

Constructor & Destructor Documentation

◆ UavcanMagnetometerBridge()

UavcanMagnetometerBridge::UavcanMagnetometerBridge ( uavcan::INode &  node)

Member Function Documentation

◆ get_name()

const char* UavcanMagnetometerBridge::get_name ( ) const
inlineoverridevirtual

Returns ASCII name of the bridge.

Implements IUavcanSensorBridge.

Definition at line 54 of file mag.hpp.

References file, init(), ioctl(), mag2_sub_cb(), mag_sub_cb(), msg, and NAME.

Here is the call graph for this function:

◆ init()

int UavcanMagnetometerBridge::init ( )
overridevirtual

Starts the bridge.

Returns
Non-negative value on success, negative on error.

Implements IUavcanSensorBridge.

Definition at line 58 of file mag.cpp.

References _sub_mag, _sub_mag2, device::CDev::init(), mag2_sub_cb(), and mag_sub_cb().

Referenced by get_name().

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

◆ ioctl()

int UavcanMagnetometerBridge::ioctl ( struct file filp,
int  cmd,
unsigned long  arg 
)
overrideprivate

Definition at line 84 of file mag.cpp.

References _scale, MAGIOCCALIBRATE, MAGIOCEXSTRAP, MAGIOCGEXTERNAL, MAGIOCGSCALE, MAGIOCSRANGE, and MAGIOCSSCALE.

Referenced by get_name().

Here is the caller graph for this function:

◆ mag2_sub_cb()

void UavcanMagnetometerBridge::mag2_sub_cb ( const uavcan::ReceivedDataStructure< uavcan::equipment::ahrs::MagneticFieldStrength2 > &  msg)
private

Definition at line 139 of file mag.cpp.

References _report, _scale, sensor_mag_s::device_id, hrt_absolute_time(), sensor_mag_s::is_external, cdev::CDev::lock(), UavcanCDevSensorBridgeBase::publish(), sensor_mag_s::timestamp, cdev::CDev::unlock(), sensor_mag_s::x, mag_calibration_s::x_offset, mag_calibration_s::x_scale, sensor_mag_s::y, mag_calibration_s::y_offset, mag_calibration_s::y_scale, sensor_mag_s::z, mag_calibration_s::z_offset, and mag_calibration_s::z_scale.

Referenced by get_name(), and init().

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

◆ mag_sub_cb()

void UavcanMagnetometerBridge::mag_sub_cb ( const uavcan::ReceivedDataStructure< uavcan::equipment::ahrs::MagneticFieldStrength > &  msg)
private

Definition at line 115 of file mag.cpp.

References _report, _scale, sensor_mag_s::device_id, hrt_absolute_time(), sensor_mag_s::is_external, cdev::CDev::lock(), UavcanCDevSensorBridgeBase::publish(), sensor_mag_s::timestamp, cdev::CDev::unlock(), sensor_mag_s::x, mag_calibration_s::x_offset, mag_calibration_s::x_scale, sensor_mag_s::y, mag_calibration_s::y_offset, mag_calibration_s::y_scale, sensor_mag_s::z, mag_calibration_s::z_offset, and mag_calibration_s::z_scale.

Referenced by get_name(), and init().

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

Member Data Documentation

◆ _report

sensor_mag_s UavcanMagnetometerBridge::_report {}
private

Definition at line 79 of file mag.hpp.

Referenced by mag2_sub_cb(), and mag_sub_cb().

◆ _scale

mag_calibration_s UavcanMagnetometerBridge::_scale {}
private

Definition at line 78 of file mag.hpp.

Referenced by ioctl(), mag2_sub_cb(), mag_sub_cb(), and UavcanMagnetometerBridge().

◆ _sub_mag

uavcan::Subscriber<uavcan::equipment::ahrs::MagneticFieldStrength, MagCbBinder> UavcanMagnetometerBridge::_sub_mag
private

Definition at line 75 of file mag.hpp.

Referenced by init().

◆ _sub_mag2

uavcan::Subscriber<uavcan::equipment::ahrs::MagneticFieldStrength2, Mag2CbBinder> UavcanMagnetometerBridge::_sub_mag2
private

Definition at line 76 of file mag.hpp.

Referenced by init().

◆ NAME

const char *const UavcanMagnetometerBridge::NAME = "mag"
static
Author
Pavel Kirienko pavel.nosp@m..kir.nosp@m.ienko.nosp@m.@gma.nosp@m.il.co.nosp@m.m

Definition at line 50 of file mag.hpp.

Referenced by get_name().


The documentation for this class was generated from the following files: