Public Member Functions | |
| bool | addOffset (microstrain_3dmgx2_imu::AddOffset::Request &req, microstrain_3dmgx2_imu::AddOffset::Response &resp) |
| bool | calibrate (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp) |
| void | calibrationStatus (diagnostic_updater::DiagnosticStatusWrapper &status) |
| void | clearErrorStatus () |
| void | ConnectTest (diagnostic_updater::DiagnosticStatusWrapper &status) |
| void | deviceStatus (diagnostic_updater::DiagnosticStatusWrapper &status) |
| void | DisconnectTest (diagnostic_updater::DiagnosticStatusWrapper &status) |
| void | doCalibrate () |
| void | getData (sensor_msgs::Imu &data) |
| std::string | getID (bool output_info=false) |
| void | GravityTest (diagnostic_updater::DiagnosticStatusWrapper &status) |
| void | GyroBiasTest (diagnostic_updater::DiagnosticStatusWrapper &status) |
| ImuNode (ros::NodeHandle h) | |
| void | InterruptionTest (diagnostic_updater::DiagnosticStatusWrapper &status) |
| void | pretest (diagnostic_updater::DiagnosticStatusWrapper &status) |
| int | publish_datum () |
| void | publish_is_calibrated () |
| void | ReadIDTest (diagnostic_updater::DiagnosticStatusWrapper &status) |
| void | ResumeTest (diagnostic_updater::DiagnosticStatusWrapper &status) |
| void | setErrorStatus (const std::string msg) |
| void | setErrorStatusf (const char *format,...) |
| bool | spin () |
| int | start () |
| int | stop () |
| void | StreamedDataTest (diagnostic_updater::DiagnosticStatusWrapper &status) |
| ~ImuNode () | |
Public Attributes | |
| ros::ServiceServer | add_offset_serv_ |
| double | angular_velocity_covariance_ |
| double | angular_velocity_stdev_ |
| bool | autocalibrate_ |
| double | bias_x_ |
| double | bias_y_ |
| double | bias_z_ |
| bool | calibrate_requested_ |
| ros::ServiceServer | calibrate_serv_ |
| bool | calibrated_ |
| microstrain_3dmgx2_imu::IMU::cmd | cmd |
| double | desired_freq_ |
| diagnostic_updater::Updater | diagnostic_ |
| int | error_count_ |
| std::string | error_status_ |
| string | frameid_ |
| diagnostic_updater::FrequencyStatus | freq_diag_ |
| microstrain_3dmgx2_imu::IMU | imu |
| ros::Publisher | imu_data_pub_ |
| ros::Publisher | is_calibrated_pub_ |
| double | linear_acceleration_covariance_ |
| double | linear_acceleration_stdev_ |
| double | max_drift_rate_ |
| ros::NodeHandle | node_handle_ |
| double | offset_ |
| double | orientation_covariance_ |
| double | orientation_stdev_ |
| string | port |
| ros::NodeHandle | private_node_handle_ |
| sensor_msgs::Imu | reading |
| bool | running |
| self_test::TestRunner | self_test_ |
| int | slow_count_ |
| std::string | was_slow_ |
Definition at line 61 of file imu_node.cc.
| ImuNode::ImuNode | ( | ros::NodeHandle | h | ) | [inline] |
Definition at line 109 of file imu_node.cc.
| ImuNode::~ImuNode | ( | ) | [inline] |
Definition at line 177 of file imu_node.cc.
| bool ImuNode::addOffset | ( | microstrain_3dmgx2_imu::AddOffset::Request & | req, | |
| microstrain_3dmgx2_imu::AddOffset::Response & | resp | |||
| ) | [inline] |
Definition at line 594 of file imu_node.cc.
| bool ImuNode::calibrate | ( | std_srvs::Empty::Request & | req, | |
| std_srvs::Empty::Response & | resp | |||
| ) | [inline] |
Definition at line 614 of file imu_node.cc.
| void ImuNode::calibrationStatus | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline] |
Definition at line 578 of file imu_node.cc.
| void ImuNode::clearErrorStatus | ( | ) | [inline] |
Definition at line 207 of file imu_node.cc.
| void ImuNode::ConnectTest | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline] |
Definition at line 407 of file imu_node.cc.
| void ImuNode::deviceStatus | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline] |
Definition at line 560 of file imu_node.cc.
| void ImuNode::DisconnectTest | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline] |
Definition at line 535 of file imu_node.cc.
| void ImuNode::doCalibrate | ( | ) | [inline] |
Definition at line 644 of file imu_node.cc.
| void ImuNode::getData | ( | sensor_msgs::Imu & | data | ) | [inline] |
Definition at line 433 of file imu_node.cc.
| std::string ImuNode::getID | ( | bool | output_info = false |
) | [inline] |
Definition at line 263 of file imu_node.cc.
| void ImuNode::GravityTest | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline] |
Definition at line 485 of file imu_node.cc.
| void ImuNode::GyroBiasTest | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline] |
Definition at line 421 of file imu_node.cc.
| void ImuNode::InterruptionTest | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline] |
Definition at line 399 of file imu_node.cc.
| void ImuNode::pretest | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline] |
Definition at line 387 of file imu_node.cc.
| int ImuNode::publish_datum | ( | ) | [inline] |
Definition at line 309 of file imu_node.cc.
| void ImuNode::publish_is_calibrated | ( | ) | [inline] |
Definition at line 380 of file imu_node.cc.
| void ImuNode::ReadIDTest | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline] |
Definition at line 414 of file imu_node.cc.
| void ImuNode::ResumeTest | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline] |
Definition at line 542 of file imu_node.cc.
| void ImuNode::setErrorStatus | ( | const std::string | msg | ) | [inline] |
Definition at line 194 of file imu_node.cc.
| void ImuNode::setErrorStatusf | ( | const char * | format, | |
| ... | ||||
| ) | [inline] |
Definition at line 182 of file imu_node.cc.
| bool ImuNode::spin | ( | ) | [inline] |
Definition at line 353 of file imu_node.cc.
| int ImuNode::start | ( | ) | [inline] |
Definition at line 212 of file imu_node.cc.
| int ImuNode::stop | ( | ) | [inline] |
Definition at line 292 of file imu_node.cc.
| void ImuNode::StreamedDataTest | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline] |
Definition at line 463 of file imu_node.cc.
| ros::ServiceServer ImuNode::add_offset_serv_ |
Definition at line 77 of file imu_node.cc.
Definition at line 100 of file imu_node.cc.
Definition at line 100 of file imu_node.cc.
Definition at line 83 of file imu_node.cc.
| double ImuNode::bias_x_ |
Definition at line 96 of file imu_node.cc.
| double ImuNode::bias_y_ |
Definition at line 97 of file imu_node.cc.
| double ImuNode::bias_z_ |
Definition at line 98 of file imu_node.cc.
Definition at line 84 of file imu_node.cc.
| ros::ServiceServer ImuNode::calibrate_serv_ |
Definition at line 78 of file imu_node.cc.
| bool ImuNode::calibrated_ |
Definition at line 85 of file imu_node.cc.
Definition at line 69 of file imu_node.cc.
| double ImuNode::desired_freq_ |
Definition at line 106 of file imu_node.cc.
| diagnostic_updater::Updater ImuNode::diagnostic_ |
Definition at line 72 of file imu_node.cc.
Definition at line 87 of file imu_node.cc.
| std::string ImuNode::error_status_ |
Definition at line 90 of file imu_node.cc.
| string ImuNode::frameid_ |
Definition at line 92 of file imu_node.cc.
| diagnostic_updater::FrequencyStatus ImuNode::freq_diag_ |
Definition at line 107 of file imu_node.cc.
Definition at line 64 of file imu_node.cc.
| ros::Publisher ImuNode::imu_data_pub_ |
Definition at line 76 of file imu_node.cc.
| ros::Publisher ImuNode::is_calibrated_pub_ |
Definition at line 79 of file imu_node.cc.
Definition at line 101 of file imu_node.cc.
Definition at line 101 of file imu_node.cc.
| double ImuNode::max_drift_rate_ |
Definition at line 104 of file imu_node.cc.
| ros::NodeHandle ImuNode::node_handle_ |
Definition at line 74 of file imu_node.cc.
| double ImuNode::offset_ |
Definition at line 94 of file imu_node.cc.
Definition at line 102 of file imu_node.cc.
| double ImuNode::orientation_stdev_ |
Definition at line 102 of file imu_node.cc.
| string ImuNode::port |
Definition at line 67 of file imu_node.cc.
| ros::NodeHandle ImuNode::private_node_handle_ |
Definition at line 75 of file imu_node.cc.
| sensor_msgs::Imu ImuNode::reading |
Definition at line 65 of file imu_node.cc.
| bool ImuNode::running |
Definition at line 81 of file imu_node.cc.
| self_test::TestRunner ImuNode::self_test_ |
Definition at line 71 of file imu_node.cc.
Definition at line 88 of file imu_node.cc.
| std::string ImuNode::was_slow_ |
Definition at line 89 of file imu_node.cc.