LLNode.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 <labust/tools/conversions.hpp>
00038 
00039 #include <sensor_msgs/NavSatFix.h>
00040 #include <tf/transform_listener.h>
00041 #include <tf/transform_broadcaster.h>
00042 #include <ros/ros.h>
00043 
00044 #include <boost/thread.hpp>
00045 
00046 struct LLNode
00047 {
00048         LLNode():
00049                 originLat(0),
00050                 originLon(0),
00051                 fixValidated(false),
00052                 fixCount(0)
00053         {
00054                 ros::NodeHandle nh,ph("~");
00055                 nh.param("LocalOriginLat",originLat,originLat);
00056                 nh.param("LocalOriginLon",originLon,originLon);
00057                 ph.param("LocalFixSim",fixValidated, fixValidated);
00058 
00059                 gps_raw = nh.subscribe<sensor_msgs::NavSatFix>("gps",1,&LLNode::onGps, this);
00060 
00061                 runner = boost::thread(boost::bind(&LLNode::publishFrame, this));
00062         }
00063 
00064         ~LLNode()
00065         {
00066                 runner.join();
00067         }
00068 
00069         void onGps(const sensor_msgs::NavSatFix::ConstPtr& fix)
00070         {
00071                 //In case we didn't have a fix on launch, but now we got 10 fixes in 15 sec.
00072                 if (!fixValidated)
00073                 {
00074                         originLat = fix->latitude;
00075                         originLon = fix->longitude;
00076                         fixValidated = true;
00077                 }
00078         };
00079 
00080         void publishFrame()
00081         {
00082                 ros::Rate rate(1);
00083                 while (ros::ok())
00084                 {
00085                         tf::Transform transform;
00086                         if (fixValidated)
00087                         {
00088                                 transform.setOrigin(tf::Vector3(originLon, originLat, 0));
00089                                 transform.setRotation(tf::createQuaternionFromRPY(0,0,0));
00090                                 broadcaster.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "/worldLatLon", "/world"));
00091                         }
00092 
00093                         transform.setOrigin(tf::Vector3(0, 0, 0));
00094                         Eigen::Quaternion<float> q;
00095                         labust::tools::quaternionFromEulerZYX(M_PI,0,M_PI/2,q);
00096                         transform.setRotation(tf::Quaternion(q.x(),q.y(),q.z(),q.w()));
00097                         broadcaster.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "/world", "local"));
00098 
00099                         rate.sleep();
00100                 }
00101         }
00102 
00103 private:
00104         ros::Subscriber gps_raw;
00105         tf::TransformBroadcaster broadcaster;
00106         double originLat, originLon;
00107         bool fixValidated;
00108         int fixCount;
00109         boost::thread runner;
00110 };
00111 
00112 int main(int argc, char* argv[])
00113 {
00114         ros::init(argc,argv,"llnode");
00115         ros::NodeHandle nh;
00116         LLNode llnode;
00117         ros::spin();
00118         return 0;
00119 }
00120 
00121 


labust_navigation
Author(s): Gyula Nagy
autogenerated on Fri Feb 7 2014 11:36:19