#include <imu.h>
Public Member Functions | |
Imu (crl::multisense::Channel *driver, std::string tf_prefix) | |
void | imuCallback (const crl::multisense::imu::Header &header) |
~Imu () | |
Private Member Functions | |
void | startStreams () |
void | stopStreams () |
Private Attributes | |
const std::string | accel_frameId_ |
ros::Publisher | accelerometer_pub_ |
ros::Publisher | accelerometer_vector_pub_ |
ros::NodeHandle | device_nh_ |
crl::multisense::Channel * | driver_ |
const std::string | gyro_frameId_ |
ros::Publisher | gyroscope_pub_ |
ros::Publisher | gyroscope_vector_pub_ |
sensor_msgs::Imu | imu_message_ |
ros::NodeHandle | imu_nh_ |
ros::Publisher | imu_pub_ |
const std::string | mag_frameId_ |
ros::Publisher | magnetometer_pub_ |
ros::Publisher | magnetometer_vector_pub_ |
boost::mutex | sub_lock_ |
const std::string | tf_prefix_ |
int32_t | total_subscribers_ |
multisense_ros::Imu::Imu | ( | crl::multisense::Channel * | driver, |
std::string | tf_prefix | ||
) |
void multisense_ros::Imu::imuCallback | ( | const crl::multisense::imu::Header & | header | ) |
void multisense_ros::Imu::startStreams | ( | ) | [private] |
void multisense_ros::Imu::stopStreams | ( | ) | [private] |
const std::string multisense_ros::Imu::accel_frameId_ [private] |
const std::string multisense_ros::Imu::gyro_frameId_ [private] |
sensor_msgs::Imu multisense_ros::Imu::imu_message_ [private] |
ros::NodeHandle multisense_ros::Imu::imu_nh_ [private] |
ros::Publisher multisense_ros::Imu::imu_pub_ [private] |
const std::string multisense_ros::Imu::mag_frameId_ [private] |
boost::mutex multisense_ros::Imu::sub_lock_ [private] |
const std::string multisense_ros::Imu::tf_prefix_ [private] |
int32_t multisense_ros::Imu::total_subscribers_ [private] |