Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #ifndef GRAFT_INCLUDE_GRAFT_GRAFT_ODOMETRY_TOPIC_H
00035 #define GRAFT_INCLUDE_GRAFT_GRAFT_ODOMETRY_TOPIC_H
00036
00037 #include <graft/GraftSensor.h>
00038 #include <ros/ros.h>
00039 #include <Eigen/Dense>
00040 #include <nav_msgs/Odometry.h>
00041 #include <tf/transform_datatypes.h>
00042 #include <numeric>
00043
00044 using namespace Eigen;
00045
00046 class GraftOdometryTopic: public GraftSensor
00047 {
00048 public:
00049 GraftOdometryTopic();
00050
00051 ~GraftOdometryTopic();
00052
00053 void callback(const nav_msgs::Odometry::ConstPtr& msg);
00054
00055 virtual graft::GraftSensorResidual::Ptr h(const graft::GraftState& state);
00056
00057 virtual graft::GraftSensorResidual::Ptr z();
00058
00059 virtual void setName(const std::string& name);
00060
00061 virtual std::string getName();
00062
00063 virtual void clearMessage();
00064
00065
00066
00067
00068
00069
00070
00071 void useAbsolutePose(bool absolute_pose);
00072
00073 void useDeltaPose(bool delta_pose);
00074
00075 void useVelocities(bool use_velocities);
00076
00077 void setTimeout(double timeout);
00078
00079 void setPoseCovariance(boost::array<double, 36>& cov);
00080
00081 void setTwistCovariance(boost::array<double, 36>& cov);
00082
00083 private:
00084 nav_msgs::Odometry::ConstPtr getMsg();
00085
00086 ros::Subscriber sub_;
00087 nav_msgs::Odometry::ConstPtr msg_;
00088 nav_msgs::Odometry::ConstPtr last_msg_;
00089
00090 std::string name_;
00091 bool absolute_pose_;
00092 bool delta_pose_;
00093 bool use_velocities_;
00094 ros::Duration timeout_;
00095
00096 boost::array<double, 36> pose_covariance_;
00097 boost::array<double, 36> twist_covariance_;
00098 };
00099
00100 #endif // GRAFT_INCLUDE_GRAFT_GRAFT_ODOMETRY_TOPIC_H