imu.h
Go to the documentation of this file.
1 
34 #ifndef MULTISENSE_ROS_IMU_H
35 #define MULTISENSE_ROS_IMU_H
36 
37 #include <mutex>
38 
39 #include <ros/ros.h>
40 
41 #include <sensor_msgs/Imu.h>
42 #include <geometry_msgs/Vector3Stamped.h>
43 
44 #include <multisense_lib/MultiSenseChannel.hh>
45 
46 namespace multisense_ros {
47 
48 class Imu {
49 public:
50 
51  Imu(crl::multisense::Channel* driver, std::string tf_prefix);
52  ~Imu();
53 
55 
56 private:
57 
58  //
59  // CRL sensor API
60 
62 
63  //
64  // Driver nodes
65 
68 
69  //
70  // multisense_ros/RawImuData publishers
71 
75 
76  //
77  // sensor_msgs/Imu publisher
79 
80  //
81  // geometry_msgs/Vector3Stamped publishers
85 
86  //
87  // IMU message
88  sensor_msgs::Imu imu_message_;
89 
90  //
91  // Publish control
92 
93  std::mutex sub_lock_;
95  void startStreams();
96  void stopStreams();
97 
98  //
99  // TF prefix and frame ID's
100  const std::string tf_prefix_;
101  std::string accel_frameId_;
102  std::string gyro_frameId_;
103  std::string mag_frameId_;
104 
106 
107 };
108 
109 }
110 
111 #endif
ros::Publisher magnetometer_vector_pub_
Definition: imu.h:84
void imuCallback(const crl::multisense::imu::Header &header)
Definition: imu.cpp:198
ros::Publisher imu_pub_
Definition: imu.h:78
sensor_msgs::Imu imu_message_
Definition: imu.h:88
int32_t total_subscribers_
Definition: imu.h:94
const std::string tf_prefix_
Definition: imu.h:100
std::string gyro_frameId_
Definition: imu.h:102
ros::Publisher gyroscope_pub_
Definition: imu.h:73
std::string mag_frameId_
Definition: imu.h:103
bool next_gen_camera_
Definition: imu.h:105
ros::Publisher magnetometer_pub_
Definition: imu.h:74
void stopStreams()
Definition: imu.cpp:322
std::mutex sub_lock_
Definition: imu.h:93
Imu(crl::multisense::Channel *driver, std::string tf_prefix)
Definition: imu.cpp:53
ros::Publisher accelerometer_vector_pub_
Definition: imu.h:82
void startStreams()
Definition: imu.cpp:307
ros::Publisher gyroscope_vector_pub_
Definition: imu.h:83
ros::Publisher accelerometer_pub_
Definition: imu.h:72
crl::multisense::Channel * driver_
Definition: imu.h:61
const std::string header
std::string accel_frameId_
Definition: imu.h:101
ros::NodeHandle imu_nh_
Definition: imu.h:67
ros::NodeHandle device_nh_
Definition: imu.h:66


multisense_ros
Author(s):
autogenerated on Sat Jun 24 2023 03:01:30