Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008 #ifndef KALMANSTATEESTIMATOR_HPP_
00009 #define KALMANSTATEESTIMATOR_HPP_
00010
00011 #include <telekyb_defines/telekyb_defines.hpp>
00012 #include <telekyb_base/Options.hpp>
00013
00014 #include <tk_state/StateEstimator.hpp>
00015 #include <EigenTools.hpp>
00016
00017 #include <pluginlib/class_list_macros.h>
00018
00019
00020 #include <sensor_msgs/Imu.h>
00021 #include <telekyb_msgs/TKState.h>
00022 #include <geometry_msgs/TransformStamped.h>
00023 #include <telekyb_base/Time.hpp>
00024
00025 #include <stdint.h>
00026 #include <deque>
00027
00028 #include <StateEstimators/ViconHandler.hpp>
00029
00030
00031 #include <boost/thread/mutex.hpp>
00032
00033 using namespace TELEKYB_NAMESPACE;
00034
00035 namespace telekyb_state {
00036
00037 class KalmanStateEstimatorOptions : public OptionContainer {
00038 public:
00039 Option<std::string>* imuTopic;
00040 Option<std::string>* viconTopic;
00041 Option<std::string>* stateTopic;
00042
00043 Option<Eigen::Matrix<double,6,6> >* imuCov;
00044 Option<Eigen::Matrix<double,6,6> >* vicCov;
00045 Option<Eigen::Matrix<double,9,9> >* discCov;
00046
00047 Option<Eigen::Matrix<double,9,9> >* initStateCov;
00048
00049
00050 Option<Eigen::Vector3d>* imuAccBias;
00051 Option<Eigen::Vector3d>* imuGyrBias;
00052
00053 Option<Eigen::Vector3d>* vicPosition;
00054 Option<Eigen::Quaterniond>* vicOrientation;
00055
00056 Option<double>* predStep;
00057 Option<double>* minStep;
00058 Option<double>* saveStep;
00059 Option<double>* lTpred;
00060
00061 Option<int>* maxStateBufferSize;
00062 Option<int>* maxMeasureBufferSize;
00063 Option<int>* maxInputBufferSize;
00064
00065 KalmanStateEstimatorOptions();
00066 };
00067
00068 class KalmanStateEstimator : public TELEKYB_NAMESPACE::StateEstimator {
00069 public:
00070
00071 virtual void initialize();
00072 virtual void willBecomeActive();
00073 virtual void willBecomeInActive();
00074 virtual void destroy();
00075
00076 virtual std::string getName() const;
00077
00078 void imuCallback(const sensor_msgs::Imu::ConstPtr& msg);
00079 void viconCallback(const geometry_msgs::TransformStamped::ConstPtr& msg);
00080
00081 protected:
00082 KalmanStateEstimatorOptions options;
00083
00084 ros::NodeHandle nodeHandle;
00085 ros::Subscriber imuSub;
00086 ros::Publisher statePub;
00087
00088 std::deque<StateBufferElement> stateBuffer;
00089 std::deque<MeasureBufferElement> measureBuffer;
00090 std::deque<InputBufferElement> inputBuffer;
00091
00092 std::deque<MeasureBufferElement>::const_iterator nextMeasureIndex;
00093 std::deque<InputBufferElement>::const_iterator currentInputIndex;
00094
00095 StateBufferElement internalState;
00096 bool isInitialized;
00097 bool isInitializedLinVel;
00098 bool isInitializedPose;
00099 bool isInitializedAngVel;
00100
00101 bool newMeasureReceived;
00102 bool newInputReceived;
00103 MeasureBufferElement newMeasure;
00104 InputBufferElement newInput;
00105
00106
00107 boost::mutex newMeasureMutex;
00108 boost::mutex newInputMutex;
00109
00110
00111
00112 void core();
00113 void prediction(StateBufferElement& state, const InputBufferElement& u, double Tpred);
00114
00115 ViconHandler viconHandler;
00116 void publishEstimate(const StateBufferElement & estimate);
00117
00118
00119 Time intTime;
00120 double predTime;
00121 Timer saveTimer;
00122
00123
00124 EigenTools tools;
00125
00126 template <typename _BufferElement>
00127 typename std::deque<_BufferElement>::iterator searchInBuffer(std::deque<_BufferElement>& buffer, double time);
00128
00129 };
00130
00131
00132 template <typename _BufferElement>
00133 typename std::deque<_BufferElement>::iterator KalmanStateEstimator::searchInBuffer(std::deque<_BufferElement>& buffer, double time) {
00134 typename std::deque<_BufferElement>::iterator current;
00135 for(current = buffer.begin(); current <= buffer.end(); current++)
00136 {
00137 if (time >= current->timeStamp) break;
00138 }
00139 return current;
00140 }
00141
00142 }
00143 #endif