ImuSim.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, LABUST, UNIZG-FER
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the LABUST nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  *  Author: Dula Nad
00035  *  Created: 01.02.2013.
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                 //Publish the imu_frame location
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 


labust_sim
Author(s): Gyula Nagy
autogenerated on Fri Feb 7 2014 11:36:33