$search
00001 00012 /************************************************************************ 00013 * Copyright (C) 2012 Eindhoven University of Technology (TU/e). * 00014 * All rights reserved. * 00015 ************************************************************************ 00016 * Redistribution and use in source and binary forms, with or without * 00017 * modification, are permitted provided that the following conditions * 00018 * are met: * 00019 * * 00020 * 1. Redistributions of source code must retain the above * 00021 * copyright notice, this list of conditions and the following * 00022 * disclaimer. * 00023 * * 00024 * 2. Redistributions in binary form must reproduce the above * 00025 * copyright notice, this list of conditions and the following * 00026 * disclaimer in the documentation and/or other materials * 00027 * provided with the distribution. * 00028 * * 00029 * THIS SOFTWARE IS PROVIDED BY TU/e "AS IS" AND ANY EXPRESS OR * 00030 * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * 00031 * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * 00032 * ARE DISCLAIMED. IN NO EVENT SHALL TU/e OR CONTRIBUTORS BE LIABLE * 00033 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * 00034 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT * 00035 * OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; * 00036 * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF * 00037 * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * 00038 * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE * 00039 * USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH * 00040 * DAMAGE. * 00041 * * 00042 * The views and conclusions contained in the software and * 00043 * documentation are those of the authors and should not be * 00044 * interpreted as representing official policies, either expressed or * 00045 * implied, of TU/e. * 00046 ************************************************************************/ 00047 00048 #include <pr2_controller_interface/controller.h> 00049 #include <pr2_mechanism_model/joint.h> 00050 #include <ros/ros.h> 00051 #include <control_toolbox/pid.h> 00052 #include <geometry_msgs/Twist.h> 00053 #include <nav_msgs/Odometry.h> 00054 #include <boost/scoped_ptr.hpp> 00055 #include <boost/thread/condition.hpp> 00056 #include <realtime_tools/realtime_publisher.h> 00057 #include <tf/transform_broadcaster.h> 00058 #include <pr2_mechanism_controllers/Odometer.h> 00059 #include <pr2_mechanism_controllers/BaseOdometryState.h> 00060 00061 namespace controller 00062 { 00063 00064 00065 class BaseOdometry : public pr2_controller_interface::Controller 00066 { 00067 private: 00072 void updateOdometry(); 00073 00078 void computeBaseVelocity(); 00079 00084 void publish(); 00085 00090 void getOdometryMessage(nav_msgs::Odometry &msg); 00091 00096 void populateCovariance(nav_msgs::Odometry &msg); 00097 00101 void publishTransform(); 00102 00103 ros::NodeHandle n; 00104 00105 pr2_mechanism_model::RobotState *robot_; 00106 00108 boost::scoped_ptr<realtime_tools::RealtimePublisher <nav_msgs::Odometry> > odometry_publisher_ ; 00109 00110 boost::scoped_ptr<realtime_tools::RealtimePublisher <tf::tfMessage> > transform_publisher_ ; 00112 00113 double odometry_publish_rate_; 00115 bool publish_odometry_, publish_tf_ ; 00117 00118 geometry_msgs::Point odometry_; 00119 geometry_msgs::Twist odometry_vel_; 00120 00121 std::string odometry_frame_; 00122 std::string base_link_frame_; 00123 std::string base_footprint_frame_; 00124 std::string tf_prefix_; 00125 00127 00128 double sigma_x_,sigma_y_,sigma_theta_,cov_x_y_,cov_x_theta_,cov_y_theta_; 00130 00132 ros::Time last_time_; 00133 ros::Time current_time_; 00134 00135 ros::Time last_odometry_publish_time_, last_transform_publish_time_; 00136 00137 double expected_publish_time_; 00138 double update_time; 00140 00142 pr2_mechanism_model::JointState* wheel_inner_left_front_state; 00143 pr2_mechanism_model::JointState* wheel_inner_left_rear_state; 00144 pr2_mechanism_model::JointState* wheel_inner_right_front_state; 00145 pr2_mechanism_model::JointState* wheel_inner_right_rear_state; 00146 double current_vel_wheel_inner_left_front, current_vel_wheel_inner_right_front, current_vel_wheel_inner_left_rear, current_vel_wheel_inner_right_rear; 00148 00150 double current_vel_x, current_vel_y, current_vel_phi; 00152 00153 public: 00154 00158 bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n); 00159 00163 void starting(); 00164 00170 void update(); 00171 00175 void stopping(); 00176 00177 }; 00178 } 00179