46 ScheduledWorkItem(MODULE_NAME,
px4::device_bus_to_wq(interface->get_device_id())),
47 _interface(interface),
177 #pragma pack(push, 1) 196 bool sensor_is_onboard =
false;
209 PX4_WARN(
"Register read error.");
214 xraw = ((rm_report.x[0] << 16) | (rm_report.x[1] << 8) | rm_report.x[2]);
215 yraw = ((rm_report.y[0] << 16) | (rm_report.y[1] << 8) | rm_report.y[2]);
216 zraw = ((rm_report.z[0] << 16) | (rm_report.z[1] << 8) | rm_report.z[2]);
224 new_mag_report.temperature = 0.0f;
229 new_mag_report.is_external = !sensor_is_onboard;
235 new_mag_report.x_raw = (int16_t)(xraw >> 8);
236 new_mag_report.y_raw = (int16_t)(yraw >> 8);
237 new_mag_report.z_raw = (int16_t)(zraw >> 8);
284 if ((*n & (1 << 23)) == (1 << 23)) {
343 PX4_ERR(
"self test failed");
383 unsigned interval = (1000000 / arg);
429 case DEVIOCGDEVICEID:
434 return CDev::ioctl(file_pointer, cmd, arg);
483 _reports->print_info(
"report queue");
503 unsigned count = buffer_len /
sizeof(
struct mag_report);
527 return ret ? ret : -EAGAIN;
561 uint8_t cmd[2] = {0, 0};
#define RM3100_CONVERSION_INTERVAL
RM3100 internal constants and data structures.
#define MAGIOCGSCALE
copy the mag scaling constants to the structure pointed to by (arg)
#define MAGIOCGEXTERNAL
determine if mag is external or onboard
perf_counter_t _conf_errors
int collect()
Collect the result of the most recent measurement.
virtual int read(struct file *file_pointer, char *buffer, size_t buffer_len)
static struct vehicle_status_s status
measure the time elapsed performing an event
int self_test()
Run sensor self-test.
perf_counter_t _sample_perf
bool _calibrated
the calibration is valid
virtual int register_class_devname(const char *class_devname)
Register a class device name, automatically adding device class instance suffix if need be...
#define SENSOR_POLLRATE_DEFAULT
poll at driver normal rate
__EXPORT void rotate_3f(enum Rotation rot, float &x, float &y, float &z)
rotate a 3 element float vector in-place
void stop()
Stop the automatic measurement state machine.
enum OPERATING_MODE _mode
perf_counter_t _comms_errors
mag scaling factors; Vout = (Vin * Vscale) + Voffset
bool _continuous_mode_set
virtual int ioctl(struct file *file_pointer, int cmd, unsigned long arg)
struct mag_calibration_s _scale
count the number of times an event occurs
int reset()
Resets the device.
#define MAGIOCSRANGE
set the measurement range to handle (at least) arg Gauss
virtual void poll_notify(pollevent_t events)
Report new poll events.
#define SENSORIOCSPOLLRATE
Set the driver polling rate to (arg) Hz, or one of the SENSOR_POLLRATE constants. ...
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
int set_default_register_values()
Configures the device with default register values.
device identifier information
void perf_count(perf_counter_t handle)
Count a performance event.
#define MAGIOCSSCALE
set the mag scaling constants to the structure pointed to by (arg)
void perf_free(perf_counter_t handle)
Free a counter.
#define MAG_BASE_DEVICE_PATH
void init()
Activates/configures the hardware registers.
#define MAGIOCCALIBRATE
perform self-calibration, update scale factors to canonical units
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...
#define DRV_MAG_DEVTYPE_RM3100
Rotation
Enum for board and external compass rotations.
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
void convert_signed(int32_t *n)
Converts int24_t stored in 32-bit container to int32_t.
RM3100(device::Device *interface, const char *path, enum Rotation rotation)
void perf_end(perf_counter_t handle)
End a performance event.
void print_info()
Diagnostics - print some basic information about the driver.
unsigned int _measure_interval
int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data)
int check_measurement()
Check whether new data is available or not.
perf_counter_t _range_errors
ringbuffer::RingBuffer * _reports
void Run() override
Performs a poll cycle; collect from the previous measurement and start a new one. ...
int measure()
Issue a measurement command.
struct @83::@85::@87 file
void perf_print_counter(perf_counter_t handle)
Print one performance counter to stdout.
#define SENSORIOCRESET
Reset the sensor to its default configuration.
uint64_t perf_event_count(perf_counter_t handle)
Return current event_count.
Fundamental base class for all physical drivers (I2C, SPI).
Shared defines for the RM3100 driver.
void start()
Initialises the automatic measurement state machine and start it.
#define RM3100_SENSITIVITY
bool _pub_blocked
true if publishing should be blocked
orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance, int priority)
void perf_begin(perf_counter_t handle)
Begin a performance event.
#define DEVICE_DEBUG(FMT,...)
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).