SSXStateEstimator.hpp
Go to the documentation of this file.
00001 /*
00002  * SSXStateEstimator.h
00003  *
00004  *  Created on: Nov 3, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef SSXSTATEESTIMATOR_HPP_
00009 #define SSXSTATEESTIMATOR_HPP_
00010 
00011 #include <telekyb_defines/telekyb_defines.hpp>
00012 #include <telekyb_base/Options.hpp>
00013 
00014 #include <tk_state/StateEstimator.hpp>
00015 
00016 // plugin stuff
00017 #include <pluginlib/class_list_macros.h>
00018 
00019 // ros
00020 #include <ros/subscriber.h>
00021 
00022 
00023 using namespace TELEKYB_NAMESPACE;
00024 
00025 namespace telekyb_state {
00026 
00027 class SSXStateEstimatorOptions : public OptionContainer {
00028 public:
00029         Option<std::string>* tSSXSeTopicName;
00030         Option<Eigen::Vector3d>* tSSXPositionOffset;
00031 
00032         SSXStateEstimatorOptions();
00033 };
00034 
00035 class SSXStateEstimator : public StateEstimator {
00036 protected:
00037         // Options
00038         SSXStateEstimatorOptions options;
00039 
00040         // ROS
00041         ros::NodeHandle nodeHandle;
00042         ros::Subscriber ssxSubscriber;
00043 
00044 
00045 public:
00046         virtual void initialize();
00047         virtual void willBecomeActive();
00048         virtual void willBecomeInActive();
00049         virtual void destroy();
00050 
00051         virtual std::string getName() const;
00052 
00053         void ssxCallback(const telekyb_msgs::TKState::ConstPtr& msg);
00054 
00055 
00056 };
00057 
00058 } //namespace
00059 
00060 #endif /* SSXSTATEESTIMATOR_HPP_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


tk_state
Author(s): Dr. Antonio Franchi and Martin Riedel
autogenerated on Mon Nov 11 2013 11:13:03