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 <tf/transform_broadcaster.h>
00042 #include <ros/ros.h>
00043
00044 #include <boost/thread/mutex.hpp>
00045
00046 struct ImuSim
00047 {
00048 ImuSim()
00049 {
00050 ros::NodeHandle nh;
00051 odom = nh.subscribe<nav_msgs::Odometry>("meas_odom",1,&ImuSim::onOdom, this);
00052 acc = nh.subscribe<geometry_msgs::Vector3>("nuacc_ideal",1,&ImuSim::onAcc, this);
00053
00054 imu_pub = nh.advertise<sensor_msgs::Imu>("imu",1);
00055 depth_pub = nh.advertise<std_msgs::Float32>("depth",1);
00056 }
00057
00058 void onOdom(const typename nav_msgs::Odometry::ConstPtr& msg)
00059 {
00060 sensor_msgs::Imu::Ptr imu(new sensor_msgs::Imu());
00061 imu->header.stamp = ros::Time::now();
00062 imu->header.frame_id = "base_link";
00063 imu->angular_velocity = msg->twist.twist.angular;
00064 imu->orientation = msg->pose.pose.orientation;
00065
00066 {
00067 boost::mutex::scoped_lock l(acc_mux);
00068 imu->linear_acceleration = nuacc;
00069 }
00070
00071 imu_pub.publish(imu);
00072
00073 std_msgs::Float32::Ptr depth(new std_msgs::Float32());
00074 depth->data = msg->pose.pose.position.z;
00075 depth_pub.publish(depth);
00076
00077
00078 tf::Transform transform;
00079 transform.setOrigin(tf::Vector3(0, 0, 0));
00080 transform.setRotation(tf::createQuaternionFromRPY(0,0,0));
00081 broadcaster.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "base_link", "imu_frame"));
00082 }
00083
00084 void onAcc(const typename geometry_msgs::Vector3::ConstPtr& msg)
00085 {
00086 boost::mutex::scoped_lock l(acc_mux);
00087 nuacc = *msg;
00088 }
00089
00090 private:
00091 ros::Subscriber odom, acc;
00092 ros::Publisher imu_pub, depth_pub;
00093 boost::mutex acc_mux;
00094 geometry_msgs::Vector3 nuacc;
00095 tf::TransformBroadcaster broadcaster;
00096 };
00097
00098 int main(int argc, char* argv[])
00099 {
00100 ros::init(argc,argv,"imu_sim");
00101 ros::NodeHandle nh;
00102 ImuSim imu;
00103 ros::spin();
00104 return 0;
00105 }
00106
00107