$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 "amigo_gazebo/pub_odometry.h" 00049 #include "pluginlib/class_list_macros.h" 00050 00052 PLUGINLIB_REGISTER_CLASS(BaseOdometryPlugin, 00053 controller::BaseOdometry, 00054 pr2_controller_interface::Controller) 00055 00056 #define WHEELRAD 0.06 00057 #define DIS2CENT 0.28991378 00058 #define HALFSQRT2 0.7071 00059 00060 using namespace controller; 00061 00062 00063 00064 bool BaseOdometry::init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) { 00065 // get parameters 00066 00067 std::string prefix_param; 00068 n.searchParam("tf_prefix", prefix_param); 00069 n.getParam(prefix_param, tf_prefix_); 00070 00071 n.param("odom/initial_x", odometry_.x, 0.0); 00072 n.param("odom/initial_y", odometry_.y, 0.0); 00073 n.param("odom/initial_yaw", odometry_.z, 0.0); 00074 n.param<std::string> ("odom_frame", odometry_frame_, "odom"); 00075 n.param<std::string> ("base_link_frame", base_link_frame_, "base_link"); 00076 n.param<std::string> ("base_footprint_frame", base_footprint_frame_, "base_link"); 00077 00078 n.param("odom_publish_rate", odometry_publish_rate_, 200.0); 00079 n.param("publish_tf", publish_tf_, true); 00080 00081 n.param<double> ("x_stddev", sigma_x_, 0.002); 00082 n.param<double> ("y_stddev", sigma_y_, 0.002); 00083 n.param<double> ("rotation_stddev", sigma_theta_, 0.017); 00084 n.param<double> ("cov_xy", cov_x_y_, 0.0); 00085 n.param<double> ("cov_xrotation", cov_x_theta_, 0.0); 00086 n.param<double> ("cov_yrotation", cov_y_theta_, 0.0); 00087 00088 std::string wheel_inner_left_front, wheel_inner_right_front, wheel_inner_left_rear, wheel_inner_right_rear; 00089 00090 //wheel_inner_left_front 00091 if (!n.getParam("wheel_inner_left_front", wheel_inner_left_front)){ 00092 ROS_ERROR("No joint given in namespace: '%s')", 00093 n.getNamespace().c_str()); 00094 return false; 00095 } 00096 00097 wheel_inner_left_front_state = robot->getJointState(wheel_inner_left_front); 00098 if (!wheel_inner_left_front_state ){ 00099 ROS_ERROR("BaseOdometry could not find joint named '%s'", 00100 wheel_inner_left_front.c_str()); 00101 return false; 00102 } 00103 00104 //wheel_inner_right_front 00105 if (!n.getParam("wheel_inner_right_front", wheel_inner_right_front)){ 00106 ROS_ERROR("No joint given in namespace: '%s')", 00107 n.getNamespace().c_str()); 00108 return false; 00109 } 00110 00111 wheel_inner_right_front_state = robot->getJointState(wheel_inner_right_front); 00112 if (!wheel_inner_right_front_state ){ 00113 ROS_ERROR("BaseOdometry could not find joint named '%s'", 00114 wheel_inner_right_front.c_str()); 00115 return false; 00116 } 00117 00118 //wheel_inner_left_rear 00119 if (!n.getParam("wheel_inner_left_rear", wheel_inner_left_rear)){ 00120 ROS_ERROR("No joint given in namespace: '%s')", 00121 n.getNamespace().c_str()); 00122 return false; 00123 } 00124 00125 wheel_inner_left_rear_state = robot->getJointState(wheel_inner_left_rear); 00126 if (!wheel_inner_left_rear_state ){ 00127 ROS_ERROR("BaseOdometry could not find joint named '%s'", 00128 wheel_inner_left_rear.c_str()); 00129 return false; 00130 } 00131 00132 //wheel_inner_right_rear 00133 if (!n.getParam("wheel_inner_right_rear", wheel_inner_right_rear)){ 00134 ROS_ERROR("No joint given in namespace: '%s')", 00135 n.getNamespace().c_str()); 00136 return false; 00137 } 00138 00139 wheel_inner_right_rear_state = robot->getJointState(wheel_inner_right_rear); 00140 if (!wheel_inner_right_rear_state ){ 00141 ROS_ERROR("BaseOdometry could not find joint named '%s'", 00142 wheel_inner_right_rear.c_str()); 00143 return false; 00144 } 00145 00146 00147 // copy robot pointer so we can access time 00148 robot_ = robot; 00149 00150 odometry_publisher_.reset(new realtime_tools::RealtimePublisher<nav_msgs::Odometry>(n,"/odom", 1)); 00151 transform_publisher_.reset(new realtime_tools::RealtimePublisher<tf::tfMessage>(n,"/tf", 1)); 00152 transform_publisher_->msg_.transforms.resize(1); 00153 00154 if(odometry_publish_rate_ <= 0.0){ 00155 expected_publish_time_ = 0.0; 00156 publish_odometry_ = false; 00157 }else{ 00158 expected_publish_time_ = 1.0/odometry_publish_rate_; 00159 publish_odometry_ = true; 00160 } 00161 00162 return true; 00163 } 00164 00165 00166 void BaseOdometry::starting() { 00167 current_time_ = robot_->getTime(); 00168 last_time_ = robot_->getTime(); 00169 last_odometry_publish_time_ = robot_->getTime(); 00170 last_transform_publish_time_ = robot_->getTime(); 00171 } 00172 00173 00174 void BaseOdometry::update() { 00175 current_time_ = robot_->getTime(); 00176 ros::Time update_start = ros::Time::now(); 00177 updateOdometry(); 00178 00179 update_time = (ros::Time::now()-update_start).toSec(); 00180 ros::Time publish_start = ros::Time::now(); 00181 00182 if(publish_odometry_) 00183 publish(); 00184 if(publish_tf_) 00185 publishTransform(); 00186 00187 last_time_ = current_time_; 00188 } 00189 00190 00191 void BaseOdometry::stopping() { 00192 } 00193 00194 00195 void BaseOdometry::updateOdometry() { 00196 double dt = (current_time_ - last_time_).toSec(); 00197 00198 computeBaseVelocity(); 00199 00200 double odom_delta_x = odometry_vel_.linear.x * dt; 00201 double odom_delta_y = odometry_vel_.linear.y * dt; 00202 double odom_delta_th = odometry_vel_.angular.z * dt; 00203 00204 odometry_.x += odom_delta_x; 00205 odometry_.y += odom_delta_y; 00206 odometry_.z += odom_delta_th; 00207 00208 ROS_DEBUG("Odometry:: Position: %f, %f, %f",odometry_.x,odometry_.y,odometry_.z); 00209 } 00210 00211 00212 void BaseOdometry::computeBaseVelocity() { 00213 current_vel_wheel_inner_left_front = wheel_inner_left_front_state->velocity_; 00214 current_vel_wheel_inner_right_front = wheel_inner_right_front_state->velocity_; 00215 current_vel_wheel_inner_left_rear = wheel_inner_left_rear_state->velocity_; 00216 current_vel_wheel_inner_right_rear = wheel_inner_right_rear_state->velocity_; 00217 00218 //conversion to current x, y and phi velocities 00219 00221 current_vel_x = 0.25*WHEELRAD*(current_vel_wheel_inner_right_front + current_vel_wheel_inner_left_front - current_vel_wheel_inner_left_rear - current_vel_wheel_inner_right_rear); 00222 current_vel_y = 0.25*WHEELRAD*(-current_vel_wheel_inner_right_front + current_vel_wheel_inner_left_front + current_vel_wheel_inner_left_rear - current_vel_wheel_inner_right_rear); 00223 00224 current_vel_phi = -0.25*WHEELRAD/DIS2CENT*(current_vel_wheel_inner_right_front+current_vel_wheel_inner_left_front+current_vel_wheel_inner_left_rear+current_vel_wheel_inner_right_rear); 00225 00226 double theta = odometry_.z; 00227 double costh = cos(theta); 00228 double sinth = sin(theta); 00229 00230 //transform to global frame 00231 odometry_vel_.linear.x = (current_vel_x * costh - current_vel_y * sinth); 00232 odometry_vel_.linear.y = (current_vel_x * sinth + current_vel_y * costh); 00233 odometry_vel_.angular.z = current_vel_phi; 00234 } 00235 00236 00237 void BaseOdometry::publish() { 00238 if(fabs((last_odometry_publish_time_ - current_time_).toSec()) < expected_publish_time_){ 00239 return; 00240 } 00241 if(odometry_publisher_->trylock()){ 00242 getOdometryMessage(odometry_publisher_->msg_); 00243 odometry_publisher_->unlockAndPublish(); 00244 last_odometry_publish_time_ = current_time_; 00245 } 00246 } 00247 00248 00249 void BaseOdometry::getOdometryMessage(nav_msgs::Odometry &msg) { 00250 msg.header.frame_id = odometry_frame_; 00251 msg.header.stamp = current_time_; 00252 msg.pose.pose.position.x = odometry_.x; 00253 msg.pose.pose.position.y = odometry_.y; 00254 msg.pose.pose.position.z = 0.0; 00255 00256 geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(odometry_.z); 00257 msg.pose.pose.orientation = odom_quat; 00258 00259 msg.twist.twist.linear.x = current_vel_x; 00260 msg.twist.twist.linear.y = current_vel_y; 00261 msg.twist.twist.angular.z = current_vel_phi; 00262 00263 populateCovariance(msg); 00264 } 00265 00266 00267 void BaseOdometry::populateCovariance(nav_msgs::Odometry &msg) { 00268 //nav_msgs::Odometry has a 6x6 covariance matrix that must be filled partly 00269 //the relations between x, y and theta are set (they are symmetrical) and 00270 //selfrelations of course (the diagonal) 00271 00272 if(fabs(odometry_vel_.linear.x) <= 1e-8 && fabs(odometry_vel_.linear.y) <= 1e-8 && fabs(odometry_vel_.angular.z) <= 1e-8){ 00273 msg.pose.covariance[0] = 1e-12; 00274 msg.pose.covariance[7] = 1e-12; 00275 msg.pose.covariance[35] = 1e-12; 00276 00277 msg.pose.covariance[1] = 1e-12; 00278 msg.pose.covariance[6] = 1e-12; 00279 00280 msg.pose.covariance[31] = 1e-12; 00281 msg.pose.covariance[11] = 1e-12; 00282 00283 msg.pose.covariance[30] = 1e-12; 00284 msg.pose.covariance[5] = 1e-12; 00285 }else{ 00286 msg.pose.covariance[0] = pow(sigma_x_,2); 00287 msg.pose.covariance[7] = pow(sigma_y_,2); 00288 msg.pose.covariance[35] = pow(sigma_theta_,2); 00289 00290 msg.pose.covariance[1] = cov_x_y_; 00291 msg.pose.covariance[6] = cov_x_y_; 00292 00293 msg.pose.covariance[31] = cov_y_theta_; 00294 msg.pose.covariance[11] = cov_y_theta_; 00295 00296 msg.pose.covariance[30] = cov_x_theta_; 00297 msg.pose.covariance[5] = cov_x_theta_; 00298 } 00299 00300 msg.pose.covariance[14] = DBL_MAX; 00301 msg.pose.covariance[21] = DBL_MAX; 00302 msg.pose.covariance[28] = DBL_MAX; 00303 00304 msg.twist.covariance = msg.pose.covariance; 00305 } 00306 00307 00308 void BaseOdometry::publishTransform() { 00309 if(fabs((last_transform_publish_time_ - current_time_).toSec()) < expected_publish_time_){ 00310 return; 00311 } 00312 if(transform_publisher_->trylock()){ 00313 00314 geometry_msgs::TransformStamped &out = transform_publisher_->msg_.transforms[0]; 00315 out.header.stamp = current_time_; 00316 out.header.frame_id = tf::resolve(tf_prefix_,odometry_frame_);//swapped with next 00317 out.child_frame_id = tf::resolve(tf_prefix_,base_footprint_frame_);//swapped with prev 00318 out.transform.translation.x = odometry_.x; 00319 out.transform.translation.y = odometry_.y; 00320 out.transform.translation.z = 0; 00321 tf::Quaternion quat_trans; 00322 quat_trans.setRPY(0.0, 0.0, odometry_.z); 00323 00324 out.transform.rotation.x = quat_trans.x(); 00325 out.transform.rotation.y = quat_trans.y(); 00326 out.transform.rotation.z = quat_trans.z(); 00327 out.transform.rotation.w = quat_trans.w(); 00328 00329 transform_publisher_->unlockAndPublish(); 00330 last_transform_publish_time_ = current_time_; 00331 } 00332 } 00333