#include <imu_ros_i.h>
|
typedef sensor_msgs::Imu | ImuMsg |
|
typedef sensor_msgs::MagneticField | MagMsg |
|
|
static std::string | getErrorDescription (int errorCode) |
|
int | setCompassCorrectionParameters (double cc_mag_field, double cc_offset0, double cc_offset1, double cc_offset2, double cc_gain0, double cc_gain1, double cc_gain2, double cc_T0, double cc_T1, double cc_T2, double cc_T3, double cc_T4, double cc_T5) |
|
void | setDataRate (int rate) |
|
void | zero () |
|
void | init (CPhidgetHandle handle) |
|
void | registerHandlers () |
|
Definition at line 22 of file imu_ros_i.h.
◆ ImuMsg
◆ MagMsg
◆ ImuRosI()
◆ attachHandler()
void phidgets::ImuRosI::attachHandler |
( |
| ) |
|
|
overrideprivatevirtual |
◆ calibrate()
void phidgets::ImuRosI::calibrate |
( |
| ) |
|
|
private |
◆ calibrateService()
bool phidgets::ImuRosI::calibrateService |
( |
std_srvs::Empty::Request & |
req, |
|
|
std_srvs::Empty::Response & |
res |
|
) |
| |
◆ dataHandler()
void phidgets::ImuRosI::dataHandler |
( |
const double |
acceleration[3], |
|
|
const double |
angularRate[3], |
|
|
const double |
magneticField[3], |
|
|
double |
timestamp |
|
) |
| |
|
overrideprivatevirtual |
◆ detachHandler()
void phidgets::ImuRosI::detachHandler |
( |
| ) |
|
|
overrideprivatevirtual |
◆ errorHandler()
void phidgets::ImuRosI::errorHandler |
( |
int |
error | ) |
|
|
overrideprivatevirtual |
◆ initDevice()
void phidgets::ImuRosI::initDevice |
( |
| ) |
|
|
private |
◆ phidgetsDiagnostics()
Main diagnostic method that takes care of collecting diagnostic data.
- Parameters
-
stat | The stat param is what is the diagnostic tasks are added two. Internally published by the diagnostic_updater package. Added for diagnostics |
Definition at line 343 of file imu_ros_i.cpp.
◆ angular_velocity_stdev_
double phidgets::ImuRosI::angular_velocity_stdev_ |
|
private |
◆ cal_publisher_
◆ cal_srv_
◆ cc_gain0_
double phidgets::ImuRosI::cc_gain0_ |
|
private |
◆ cc_gain1_
double phidgets::ImuRosI::cc_gain1_ |
|
private |
◆ cc_gain2_
double phidgets::ImuRosI::cc_gain2_ |
|
private |
◆ cc_mag_field_
double phidgets::ImuRosI::cc_mag_field_ |
|
private |
◆ cc_offset0_
double phidgets::ImuRosI::cc_offset0_ |
|
private |
◆ cc_offset1_
double phidgets::ImuRosI::cc_offset1_ |
|
private |
◆ cc_offset2_
double phidgets::ImuRosI::cc_offset2_ |
|
private |
◆ cc_T0_
double phidgets::ImuRosI::cc_T0_ |
|
private |
◆ cc_T1_
double phidgets::ImuRosI::cc_T1_ |
|
private |
◆ cc_T2_
double phidgets::ImuRosI::cc_T2_ |
|
private |
◆ cc_T3_
double phidgets::ImuRosI::cc_T3_ |
|
private |
◆ cc_T4_
double phidgets::ImuRosI::cc_T4_ |
|
private |
◆ cc_T5_
double phidgets::ImuRosI::cc_T5_ |
|
private |
◆ diag_updater_
updater object of class Update. Used to add diagnostic tasks, set ID etc. refer package API. Added for diagnostics
Definition at line 43 of file imu_ros_i.h.
◆ error_number_
int phidgets::ImuRosI::error_number_ |
|
private |
◆ frame_id_
◆ imu_msg_
ImuMsg phidgets::ImuRosI::imu_msg_ |
|
private |
◆ imu_publisher_
◆ imu_publisher_diag_ptr_
◆ is_connected_
bool phidgets::ImuRosI::is_connected_ |
|
private |
◆ last_published_time_
ros::Time phidgets::ImuRosI::last_published_time_ |
|
private |
◆ linear_acceleration_stdev_
double phidgets::ImuRosI::linear_acceleration_stdev_ |
|
private |
◆ mag_msg_
MagMsg phidgets::ImuRosI::mag_msg_ |
|
private |
◆ mag_publisher_
◆ magnetic_field_stdev_
double phidgets::ImuRosI::magnetic_field_stdev_ |
|
private |
◆ nh_
◆ nh_private_
◆ period_
int phidgets::ImuRosI::period_ |
|
private |
◆ serial_number_
int phidgets::ImuRosI::serial_number_ |
|
private |
◆ target_publish_freq_
double phidgets::ImuRosI::target_publish_freq_ |
|
private |
◆ time_zero_
◆ use_imu_time_
bool phidgets::ImuRosI::use_imu_time_ |
|
private |
The documentation for this class was generated from the following files: