00001 /* 00002 * Copyright (c) 2013, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 /* 00031 * Author: Chad Rockey 00032 */ 00033 00034 #include <iostream> 00035 #include <Eigen/Dense> 00036 #include <ros/ros.h> 00037 #include <graft/GraftParameterManager.h> 00038 #include <graft/GraftSensor.h> 00039 #include <graft/GraftOdometryTopic.h> 00040 #include <graft/GraftImuTopic.h> 00041 #include <graft/GraftUKFAbsolute.h> 00042 #include <graft/GraftState.h> 00043 #include <tf/transform_broadcaster.h> 00044 00045 GraftUKFAbsolute ukfv; 00046 00047 ros::Publisher state_pub; 00048 ros::Publisher odom_pub; 00049 00050 nav_msgs::Odometry odom_; 00051 00052 // tf 00053 bool publish_tf_; 00054 boost::shared_ptr<tf::TransformBroadcaster> broadcaster_; 00055 00056 std::string parent_frame_id_; 00057 std::string child_frame_id_; 00058 00059 void publishTF(const nav_msgs::Odometry& msg){ 00060 geometry_msgs::TransformStamped tf; 00061 tf.header.stamp = msg.header.stamp; 00062 tf.header.frame_id = msg.header.frame_id; 00063 tf.child_frame_id = msg.child_frame_id; 00064 00065 tf.transform.translation.x = msg.pose.pose.position.x; 00066 tf.transform.translation.y = msg.pose.pose.position.y; 00067 tf.transform.translation.z = msg.pose.pose.position.z; 00068 tf.transform.rotation = msg.pose.pose.orientation; 00069 00070 broadcaster_->sendTransform(tf); 00071 } 00072 00073 void timer_callback(const ros::TimerEvent& event){ 00074 double dt = ukfv.predictAndUpdate(); 00075 00076 graft::GraftState state = *ukfv.getMessageFromState(); 00077 state.header.stamp = ros::Time::now(); 00078 state_pub.publish(state); 00079 00080 // Update Odometry 00081 odom_.header.stamp = ros::Time::now(); 00082 odom_.header.frame_id = parent_frame_id_; 00083 odom_.child_frame_id = child_frame_id_; 00084 odom_.pose.pose = state.pose; 00085 odom_.twist.twist = state.twist; 00086 odom_pub.publish(odom_); 00087 if(publish_tf_){ 00088 publishTF(odom_); 00089 } 00090 } 00091 00092 int main(int argc, char **argv) 00093 { 00094 ros::init(argc, argv, "graft_ukf_velocity"); 00095 ros::NodeHandle n; 00096 ros::NodeHandle pnh("~"); 00097 state_pub = pnh.advertise<graft::GraftState>("state", 5); 00098 odom_pub = n.advertise<nav_msgs::Odometry>("odom_combined", 5); 00099 00100 // Load parameters 00101 std::vector<boost::shared_ptr<GraftSensor> > topics; 00102 std::vector<ros::Subscriber> subs; 00103 GraftParameterManager manager(n, pnh); 00104 manager.loadParameters(topics, subs); 00105 00106 publish_tf_ = manager.getPublishTF(); 00107 00108 parent_frame_id_ = manager.getParentFrameID(); 00109 child_frame_id_ = manager.getChildFrameID(); 00110 00111 // Set up the E 00112 std::vector<double> initial_covariance = manager.getInitialCovariance(); 00113 std::vector<double> Q = manager.getProcessNoise(); 00114 ukfv.setAlpha(manager.getAlpha()); 00115 ukfv.setKappa(manager.getKappa()); 00116 ukfv.setBeta(manager.getBeta()); 00117 ukfv.setInitialCovariance(initial_covariance); 00118 ukfv.setProcessNoise(Q); 00119 ukfv.setTopics(topics); 00120 00121 odom_.pose.pose.position.x = 0.0; 00122 odom_.pose.pose.position.y = 0.0; 00123 odom_.pose.pose.position.z = 0.0; 00124 00125 odom_.pose.pose.orientation.w = 1.0; 00126 odom_.pose.pose.orientation.x = 0.0; 00127 odom_.pose.pose.orientation.y = 0.0; 00128 odom_.pose.pose.orientation.z = 0.0; 00129 00130 odom_.twist.twist.linear.x = 0.0; 00131 odom_.twist.twist.linear.y = 0.0; 00132 odom_.twist.twist.linear.z = 0.0; 00133 odom_.twist.twist.angular.x = 0.0; 00134 odom_.twist.twist.angular.y = 0.0; 00135 odom_.twist.twist.angular.z = 0.0; 00136 00137 // Tf Broadcaster 00138 broadcaster_.reset(new tf::TransformBroadcaster()); 00139 00140 // Start loop 00141 ros::Timer timer = n.createTimer(ros::Duration(1.0/manager.getUpdateRate()), timer_callback); 00142 00143 // Spin 00144 ros::spin(); 00145 }