#include <ros/ros.h>
#include <sensor_msgs/Imu.h>
#include <geometry_msgs/Vector3Stamped.h>
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <tf/transform_listener.h>
#include <string>
#include <utility>
Go to the source code of this file.
Functions | |
void | imuData_cb (const geometry_msgs::Vector3Stamped::ConstPtr &accel_msg, const geometry_msgs::Vector3Stamped::ConstPtr &gyro_msg) |
Callback publishing imu messages. | |
int | main (int argc, char **argv) |
Variables | |
ros::Publisher | publisher |
tf::TransformListener * | tf_listener |
std::string | tf_prefix |
void imuData_cb | ( | const geometry_msgs::Vector3Stamped::ConstPtr & | accel_msg, |
const geometry_msgs::Vector3Stamped::ConstPtr & | gyro_msg | ||
) |
Callback publishing imu messages.
Fuses accelerometer and gyro messages to imu message
Definition at line 25 of file imu_provider.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 74 of file imu_provider.cpp.
Definition at line 15 of file imu_provider.cpp.
Definition at line 18 of file imu_provider.cpp.
std::string tf_prefix |
Definition at line 12 of file imu_provider.cpp.