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 #ifndef GRAFT_INCLUDE_GRAFT_GRAFT_PARAMETER_MANAGER_H 00035 #define GRAFT_INCLUDE_GRAFT_GRAFT_PARAMETER_MANAGER_H 00036 00037 #include <ros/ros.h> 00038 #include <graft/GraftSensor.h> 00039 00040 #include <graft/GraftOdometryTopic.h> 00041 #include <graft/GraftImuTopic.h> 00042 00043 class GraftParameterManager 00044 { 00045 public: 00046 GraftParameterManager(ros::NodeHandle n, ros::NodeHandle pnh); 00047 00048 ~GraftParameterManager(); 00049 00050 void loadParameters(std::vector<boost::shared_ptr<GraftSensor> >& topics, std::vector<ros::Subscriber>& subs); 00051 00052 void parseNavMsgsOdometryParameters(ros::NodeHandle& tnh, boost::shared_ptr<GraftOdometryTopic>& odom); 00053 00054 void parseSensorMsgsIMUParameters(ros::NodeHandle& tnh, boost::shared_ptr<GraftImuTopic>& imu); 00055 00056 std::string getFilterType(); 00057 00058 bool getPlanarOutput(); 00059 00060 std::string getParentFrameID(); 00061 00062 std::string getChildFrameID(); 00063 00064 double getUpdateRate(); 00065 00066 std::string getUpdateTopic(); 00067 00068 double getdtOveride(); 00069 00070 int getQueueSize(); 00071 00072 bool getIncludePose(); 00073 00074 bool getPublishTF(); 00075 00076 std::vector<double> getInitialCovariance(); 00077 00078 std::vector<double> getProcessNoise(); 00079 00080 double getAlpha(); 00081 00082 double getKappa(); 00083 00084 double getBeta(); 00085 00086 private: 00087 00088 ros::NodeHandle n_; 00089 ros::NodeHandle pnh_; 00090 00091 std::string filter_type_; // EKF or UKF 00092 bool planar_output_; // Output in 2D instead of 3D 00093 std::string parent_frame_id_; 00094 std::string child_frame_id_; 00095 double update_rate_; // How often to update 00096 std::string update_topic_; // Update when this topic arrives 00097 double dt_override_; // Overrides the dt between updates, ignored if 0 00098 int queue_size_; 00099 bool publish_tf_; 00100 std::vector<double> initial_covariance_; 00101 std::vector<double> process_noise_; 00102 double alpha_; 00103 double kappa_; 00104 double beta_; 00105 00106 // Derived parameters for filter behavior 00107 bool include_pose_; 00108 }; 00109 00110 #endif // GRAFT_INCLUDE_GRAFT_GRAFT_PARAMETER_MANAGER_H