35 #include <multisense_ros/RawImuData.h> 36 #include <std_msgs/Time.h> 47 void imuCB(
const imu::Header& header,
void* userDataP)
48 {
reinterpret_cast<Imu*
>(userDataP)->imuCallback(header); }
53 Imu::Imu(
Channel* driver, std::string tf_prefix) :
56 imu_nh_(device_nh_,
"imu"),
61 accelerometer_vector_pub_(),
62 gyroscope_vector_pub_(),
63 magnetometer_vector_pub_(),
66 total_subscribers_(0),
67 tf_prefix_(tf_prefix),
68 accel_frameId_(tf_prefix_ +
"/accel"),
69 gyro_frameId_(tf_prefix_ +
"/gyro"),
70 mag_frameId_(tf_prefix_ +
"/mag")
86 imu_message_.linear_acceleration_covariance[0] = 6.98179077e-04;
87 imu_message_.linear_acceleration_covariance[1] = 2.46789341e-06;
88 imu_message_.linear_acceleration_covariance[2] =-2.50549745e-06;
89 imu_message_.linear_acceleration_covariance[3] = 2.46789341e-06;
90 imu_message_.linear_acceleration_covariance[4] = 5.02177646e-04;
91 imu_message_.linear_acceleration_covariance[5] = 5.26265558e-05;
92 imu_message_.linear_acceleration_covariance[6] =-2.50549745e-06;
93 imu_message_.linear_acceleration_covariance[7] = 5.26265558e-05;
94 imu_message_.linear_acceleration_covariance[8] = 9.22796937e-04;
96 imu_message_.angular_velocity_covariance[0] = 8.79376936e-06;
97 imu_message_.angular_velocity_covariance[1] = -3.56007627e-07;
98 imu_message_.angular_velocity_covariance[2] = 2.22611968e-07;
99 imu_message_.angular_velocity_covariance[3] = -3.56007627e-07;
100 imu_message_.angular_velocity_covariance[4] = 8.78939245e-06;
101 imu_message_.angular_velocity_covariance[5] = -8.08367486e-07;
102 imu_message_.angular_velocity_covariance[6] = 1.33981577e-05;
103 imu_message_.angular_velocity_covariance[7] = 2.22611968e-07;
104 imu_message_.angular_velocity_covariance[8] = -8.08367486e-07;
111 if (Status_Ok != status) {
112 ROS_ERROR(
"IMU: failed to query device info: %s",
113 Channel::statusString(status));
118 ROS_INFO(
"hardware does not support an IMU");
124 if (Status_Ok != status) {
125 ROS_ERROR(
"IMU: Unable to query sensor firmware version: %s",
126 Channel::statusString(status));
132 ROS_WARN(
"IMU support requires sensor firmware v2.3 or greater (sensor is running v%d.%d)",
176 std::vector<imu::Sample>::const_iterator it = header.
samples.begin();
186 for(; it != header.
samples.end(); ++it) {
190 multisense_ros::RawImuData msg;
191 geometry_msgs::Vector3Stamped vector_msg;
199 vector_msg.header.stamp = msg.time_stamp;
200 vector_msg.vector.x = s.
x;
201 vector_msg.vector.y = s.
y;
202 vector_msg.vector.z = s.
z;
207 case imu::Sample::Type_Accelerometer:
216 if (accel_subscribers > 0)
219 if (imu_subscribers > 0)
222 if (accel_vector_subscribers > 0) {
228 case imu::Sample::Type_Gyroscope:
242 if (gyro_subscribers > 0)
245 if (imu_subscribers > 0)
248 if (gyro_vector_subscribers > 0) {
254 case imu::Sample::Type_Magnetometer:
257 if (mag_subscribers > 0)
260 if (mag_vector_subscribers > 0) {
275 if (Status_Ok != status)
276 ROS_ERROR(
"IMU: failed to start streams: %s",
277 Channel::statusString(status));
295 if (Status_Ok != status)
296 ROS_ERROR(
"IMU: failed to stop streams: %s",
297 Channel::statusString(status));
const std::string mag_frameId_
virtual Status startStreams(DataSource mask)=0
ros::Publisher magnetometer_vector_pub_
void imuCallback(const crl::multisense::imu::Header &header)
const std::string accel_frameId_
void publish(const boost::shared_ptr< M > &message) const
sensor_msgs::Imu imu_message_
int32_t total_subscribers_
virtual Status stopStreams(DataSource mask)=0
ros::Publisher gyroscope_pub_
virtual Status getVersionInfo(system::VersionInfo &v)=0
ros::Publisher magnetometer_pub_
virtual Status removeIsolatedCallback(image::Callback callback)=0
virtual Status addIsolatedCallback(image::Callback callback, DataSource imageSourceMask, void *userDataP=NULL)=0
uint32_t hardwareRevision
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher accelerometer_vector_pub_
VersionType sensorFirmwareVersion
const std::string gyro_frameId_
ros::Publisher gyroscope_vector_pub_
uint32_t getNumSubscribers() const
ros::Publisher accelerometer_pub_
crl::multisense::Channel * driver_
virtual Status getDeviceInfo(system::DeviceInfo &info)=0
uint32_t timeMicroSeconds