#include <imupublisher.h>
Public Member Functions | |
ImuPublisher (ros::NodeHandle &node) | |
void | operator() (const XsDataPacket &packet, ros::Time timestamp) |
Public Attributes | |
double | angular_velocity_variance [3] |
double | expected_frequency |
std::string | frame_id = DEFAULT_FRAME_ID |
double | frequency_tolerance = 0.1 |
ros::Publisher | inner_pub |
double | linear_acceleration_variance [3] |
double | orientation_variance [3] |
diagnostic_updater::DiagnosedPublisher< sensor_msgs::Imu > | pub |
diagnostic_updater::Updater | updater |
Definition at line 61 of file imupublisher.h.
|
inline |
Definition at line 75 of file imupublisher.h.
|
inlinevirtual |
Implements PacketCallback.
Definition at line 90 of file imupublisher.h.
double ImuPublisher::angular_velocity_variance[3] |
Definition at line 73 of file imupublisher.h.
double ImuPublisher::expected_frequency |
Definition at line 65 of file imupublisher.h.
std::string ImuPublisher::frame_id = DEFAULT_FRAME_ID |
Definition at line 68 of file imupublisher.h.
double ImuPublisher::frequency_tolerance = 0.1 |
Definition at line 66 of file imupublisher.h.
ros::Publisher ImuPublisher::inner_pub |
Definition at line 63 of file imupublisher.h.
double ImuPublisher::linear_acceleration_variance[3] |
Definition at line 72 of file imupublisher.h.
double ImuPublisher::orientation_variance[3] |
Definition at line 71 of file imupublisher.h.
diagnostic_updater::DiagnosedPublisher<sensor_msgs::Imu> ImuPublisher::pub |
Definition at line 67 of file imupublisher.h.
diagnostic_updater::Updater ImuPublisher::updater |
Definition at line 64 of file imupublisher.h.