rosie_odometry.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00039 #define EIGEN2_SUPPORT
00040 
00041 #include <Eigen/SVD>
00042 #include <nav_msgs/Odometry.h>
00043 #include <realtime_tools/realtime_publisher.h>
00044 #include <tf/tfMessage.h>
00045 #include <tf/tf.h>
00046 #include <pr2_mechanism_controllers/base_kinematics.h>
00047 #include <angles/angles.h>
00048 
00049 #include <boost/scoped_ptr.hpp>
00050 
00051 typedef Eigen::Matrix<float, 3, 1> OdomMatrix3x1;
00052 typedef Eigen::Matrix<float, 16, 1> OdomMatrix16x1;
00053 typedef Eigen::Matrix<float, 16, 3> OdomMatrix16x3;
00054 typedef Eigen::Matrix<float, 16, 16> OdomMatrix16x16;
00055 
00056 namespace controller
00057 {
00061   class RosieOdometry : public pr2_controller_interface::Controller
00062   {
00063     public:
00064 
00068     RosieOdometry();
00069 
00073     ~RosieOdometry();
00074 
00081     bool initXml(pr2_mechanism_model::RobotState *robot_state, TiXmlElement *config);
00082 
00089     bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node);
00090 
00091     /*
00092     * \brief  The starting method is called by the realtime thread just before
00093     * the first call to update.  Overrides Controller.staring().
00094     * @return Successful start
00095     */
00096     void starting();
00097 
00102     void update();
00103 
00107     void publish();
00108 
00109 
00110     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00111 
00112     private:
00113 
00114     ros::NodeHandle node_;
00115 
00119     BaseKinematics base_kin_;
00120 
00124     void updateOdometry();
00125 
00130     void getOdometryMessage(nav_msgs::Odometry &msg);
00131 
00141     void getOdometry(double &x, double &y, double &yaw, double &vx, double &vy, double &vw);
00142 
00148     void getOdometry(geometry_msgs::Point &odom, geometry_msgs::Twist &odom_vel);
00149 
00153     void computeBaseVelocity();
00154 
00159     double getCorrectedWheelSpeed(int index);
00160 
00164     Eigen::MatrixXf iterativeLeastSquares(Eigen::MatrixXf lhs, Eigen::MatrixXf rhs, std::string weight_type, int max_iter);
00165 
00169     Eigen::MatrixXf findWeightMatrix(Eigen::MatrixXf residual, std::string weight_type);
00170 
00174     double odometer_distance_;
00175 
00179     double odometer_angle_;
00180 
00184     ros::Time last_time_,current_time_;
00185 
00189     Eigen::MatrixXf cbv_rhs_, fit_rhs_, fit_residual_, odometry_residual_, cbv_lhs_, fit_lhs_, cbv_soln_,fit_soln_,  weight_matrix_;
00190 
00194     geometry_msgs::Point odom_;
00195 
00199     geometry_msgs::Twist odom_vel_;
00200 
00204     std::string ils_weight_type_;
00205 
00209     int ils_max_iterations_;
00210 
00214     double odometry_residual_max_;
00215 
00219     std::string odom_frame_;
00220 
00224     std::string base_link_frame_;
00225 
00226 
00230     ros::Time last_publish_time_;
00231 
00235     double expected_publish_time_;
00236 
00240     boost::scoped_ptr<realtime_tools::RealtimePublisher <nav_msgs::Odometry> > odometry_publisher_ ;
00241 
00245     boost::scoped_ptr<realtime_tools::RealtimePublisher <tf::tfMessage> > transform_publisher_ ;
00246 
00247     double sigma_x_,sigma_y_,sigma_theta_,cov_x_y_,cov_x_theta_,cov_y_theta_;
00248 
00249 
00253     void populateCovariance(double residual, nav_msgs::Odometry &msg);
00254 
00255   };
00256 }


ias_mechanism_controllers
Author(s): Lorenz Moesenlechner, Ingo Kresse
autogenerated on Mon Oct 6 2014 08:19:58