Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 #include <nav_msgs/Odometry.h>
00038 #include <geometry_msgs/Vector3.h>
00039 #include <sensor_msgs/Imu.h>
00040 #include <std_msgs/Float32.h>
00041 #include <tf2_ros/transform_broadcaster.h>
00042 #include <geometry_msgs/TransformStamped.h>
00043 #include <ros/ros.h>
00044 #include <labust/tools/conversions.hpp>
00045 
00046 #include <boost/thread/mutex.hpp>
00047 
00048 struct ImuSim
00049 {
00050         ImuSim()
00051         {
00052                 ros::NodeHandle nh;
00053                 odom = nh.subscribe<nav_msgs::Odometry>("meas_odom",1,&ImuSim::onOdom, this);
00054                 acc = nh.subscribe<geometry_msgs::Vector3>("nuacc_ideal",1,&ImuSim::onAcc, this);
00055 
00056                 imu_pub = nh.advertise<sensor_msgs::Imu>("imu",1);
00057                 depth_pub = nh.advertise<std_msgs::Float32>("depth",1);
00058         }
00059 
00060         void onOdom(const typename nav_msgs::Odometry::ConstPtr& msg)
00061         {
00062                 sensor_msgs::Imu::Ptr imu(new sensor_msgs::Imu());
00063                 imu->header.stamp = ros::Time::now();
00064                 imu->header.frame_id = "base_link";
00065                 imu->angular_velocity = msg->twist.twist.angular;
00066                 imu->orientation = msg->pose.pose.orientation;
00067 
00068                 {
00069                         boost::mutex::scoped_lock l(acc_mux);
00070                         imu->linear_acceleration = nuacc;
00071                 }
00072 
00073                 imu_pub.publish(imu);
00074 
00075                 std_msgs::Float32::Ptr depth(new std_msgs::Float32());
00076                 depth->data = msg->pose.pose.position.z;
00077                 depth_pub.publish(depth);
00078 
00079                 
00081                 geometry_msgs::TransformStamped transform;
00082                 transform.transform.translation.x = 0;
00083                 transform.transform.translation.y = 0;
00084                 transform.transform.translation.z = 0;
00085                 labust::tools::quaternionFromEulerZYX(0, 0, 0,
00086                                 transform.transform.rotation);
00087                 transform.child_frame_id = "imu_frame";
00088                 transform.header.frame_id = "base_link";
00089                 transform.header.stamp = ros::Time::now();
00090                 broadcaster.sendTransform(transform);
00091         }
00092 
00093         void onAcc(const typename geometry_msgs::Vector3::ConstPtr& msg)
00094         {
00095                 boost::mutex::scoped_lock l(acc_mux);
00096                 nuacc = *msg;
00097         }
00098 
00099 private:
00100         ros::Subscriber odom, acc;
00101         ros::Publisher imu_pub, depth_pub;
00102         boost::mutex acc_mux;
00103         geometry_msgs::Vector3 nuacc;
00104         tf2_ros::TransformBroadcaster broadcaster;
00105 };
00106 
00107 int main(int argc, char* argv[])
00108 {
00109         ros::init(argc,argv,"imu_sim");
00110         ros::NodeHandle nh;
00111         ImuSim imu;
00112         ros::spin();
00113         return 0;
00114 }
00115 
00116