gazebo_ros_kobuki_updates.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2013, Yujin Robot.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of Yujin Robot nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00036 #include "kobuki_gazebo_plugins/gazebo_ros_kobuki.h"
00037 
00038 
00039 namespace gazebo {
00040 
00041 
00042 void GazeboRosKobuki::updateJointState()
00043 {
00044   /*
00045    * Joint states
00046    */
00047   std::string baselink_frame = gazebo_ros_->resolveTF("base_link");
00048   joint_state_.header.stamp = ros::Time::now();
00049   joint_state_.header.frame_id = baselink_frame;
00050   joint_state_.position[LEFT] = joints_[LEFT]->GetAngle(0).Radian();
00051   joint_state_.velocity[LEFT] = joints_[LEFT]->GetVelocity(0);
00052   joint_state_.position[RIGHT] = joints_[RIGHT]->GetAngle(0).Radian();
00053   joint_state_.velocity[RIGHT] = joints_[RIGHT]->GetVelocity(0);
00054   joint_state_pub_.publish(joint_state_);
00055 }
00056 
00057 /*
00058  * Odometry (encoders & IMU)
00059  */
00060 void GazeboRosKobuki::updateOdometry(common::Time& step_time)
00061 {
00062   std::string odom_frame = gazebo_ros_->resolveTF("odom");
00063   std::string base_frame = gazebo_ros_->resolveTF("base_footprint");
00064   odom_.header.stamp = joint_state_.header.stamp;
00065   odom_.header.frame_id = odom_frame;
00066   odom_.child_frame_id = base_frame;
00067 
00068   // Distance travelled by main wheels
00069   double d1, d2;
00070   double dr, da;
00071   d1 = d2 = 0;
00072   dr = da = 0;
00073   d1 = step_time.Double() * (wheel_diam_ / 2) * joints_[LEFT]->GetVelocity(0);
00074   d2 = step_time.Double() * (wheel_diam_ / 2) * joints_[RIGHT]->GetVelocity(0);
00075   // Can see NaN values here, just zero them out if needed
00076   if (isnan(d1))
00077   {
00078     ROS_WARN_STREAM_THROTTLE(0.1, "Gazebo ROS Kobuki plugin: NaN in d1. Step time: " << step_time.Double()
00079                              << ", WD: " << wheel_diam_ << ", velocity: " << joints_[LEFT]->GetVelocity(0));
00080     d1 = 0;
00081   }
00082   if (isnan(d2))
00083   {
00084     ROS_WARN_STREAM_THROTTLE(0.1, "Gazebo ROS Kobuki plugin: NaN in d2. Step time: " << step_time.Double()
00085                              << ", WD: " << wheel_diam_ << ", velocity: " << joints_[RIGHT]->GetVelocity(0));
00086     d2 = 0;
00087   }
00088   dr = (d1 + d2) / 2;
00089   da = (d2 - d1) / wheel_sep_; // ignored
00090 
00091   // Just as in the Kobuki driver, the angular velocity is taken directly from the IMU
00092   vel_angular_ = imu_->GetAngularVelocity();
00093 
00094   // Compute odometric pose
00095   odom_pose_[0] += dr * cos( odom_pose_[2] );
00096   odom_pose_[1] += dr * sin( odom_pose_[2] );
00097   odom_pose_[2] += vel_angular_.z * step_time.Double();
00098   // Compute odometric instantaneous velocity
00099   odom_vel_[0] = dr / step_time.Double();
00100   odom_vel_[1] = 0.0;
00101   odom_vel_[2] = vel_angular_.z;
00102 
00103   odom_.pose.pose.position.x = odom_pose_[0];
00104   odom_.pose.pose.position.y = odom_pose_[1];
00105   odom_.pose.pose.position.z = 0;
00106 
00107   tf::Quaternion qt;
00108   qt.setEuler(0,0,odom_pose_[2]);
00109   odom_.pose.pose.orientation.x = qt.getX();
00110   odom_.pose.pose.orientation.y = qt.getY();
00111   odom_.pose.pose.orientation.z = qt.getZ();
00112   odom_.pose.pose.orientation.w = qt.getW();
00113 
00114   odom_.pose.covariance[0]  = 0.1;
00115   odom_.pose.covariance[7]  = 0.1;
00116   odom_.pose.covariance[35] = 0.05;
00117   odom_.pose.covariance[14] = 1e6;
00118   odom_.pose.covariance[21] = 1e6;
00119   odom_.pose.covariance[28] = 1e6;
00120 
00121   odom_.twist.twist.linear.x = odom_vel_[0];
00122   odom_.twist.twist.linear.y = 0;
00123   odom_.twist.twist.linear.z = 0;
00124   odom_.twist.twist.angular.x = 0;
00125   odom_.twist.twist.angular.y = 0;
00126   odom_.twist.twist.angular.z = odom_vel_[2];
00127   odom_pub_.publish(odom_); // publish odom message
00128 
00129   if (publish_tf_)
00130   {
00131     odom_tf_.header = odom_.header;
00132     odom_tf_.child_frame_id = odom_.child_frame_id;
00133     odom_tf_.transform.translation.x = odom_.pose.pose.position.x;
00134     odom_tf_.transform.translation.y = odom_.pose.pose.position.y;
00135     odom_tf_.transform.translation.z = odom_.pose.pose.position.z;
00136     odom_tf_.transform.rotation = odom_.pose.pose.orientation;
00137     tf_broadcaster_.sendTransform(odom_tf_);
00138   }
00139 }
00140 
00141 /*
00142  * Publish IMU data
00143  */
00144 void GazeboRosKobuki::updateIMU()
00145 {
00146   imu_msg_.header = joint_state_.header;
00147   math::Quaternion quat = imu_->GetOrientation();
00148   imu_msg_.orientation.x = quat.x;
00149   imu_msg_.orientation.y = quat.y;
00150   imu_msg_.orientation.z = quat.z;
00151   imu_msg_.orientation.w = quat.w;
00152   imu_msg_.orientation_covariance[0] = 1e6;
00153   imu_msg_.orientation_covariance[4] = 1e6;
00154   imu_msg_.orientation_covariance[8] = 0.05;
00155   imu_msg_.angular_velocity.x = vel_angular_.x;
00156   imu_msg_.angular_velocity.y = vel_angular_.y;
00157   imu_msg_.angular_velocity.z = vel_angular_.z;
00158   imu_msg_.angular_velocity_covariance[0] = 1e6;
00159   imu_msg_.angular_velocity_covariance[4] = 1e6;
00160   imu_msg_.angular_velocity_covariance[8] = 0.05;
00161   math::Vector3 lin_acc = imu_->GetLinearAcceleration();
00162   imu_msg_.linear_acceleration.x = lin_acc.x;
00163   imu_msg_.linear_acceleration.y = lin_acc.y;
00164   imu_msg_.linear_acceleration.z = lin_acc.z;
00165   imu_pub_.publish(imu_msg_); // publish odom message
00166 }
00167 
00168 /*
00169  * Propagate velocity commands
00170  * TODO: Check how to simulate disabled motors, e.g. set MaxForce to zero, but then damping is important!
00171  */
00172 void GazeboRosKobuki::propagateVelocityCommands()
00173 {
00174   if (((prev_update_time_- last_cmd_vel_time_).Double() > cmd_vel_timeout_) || !motors_enabled_)
00175   {
00176     wheel_speed_cmd_[LEFT] = 0.0;
00177     wheel_speed_cmd_[RIGHT] = 0.0;
00178   }
00179   joints_[LEFT]->SetVelocity(0, wheel_speed_cmd_[LEFT] / (wheel_diam_ / 2.0));
00180   joints_[RIGHT]->SetVelocity(0, wheel_speed_cmd_[RIGHT] / (wheel_diam_ / 2.0));
00181   joints_[LEFT]->SetMaxForce(0, torque_);
00182   joints_[RIGHT]->SetMaxForce(0, torque_);
00183 }
00184 
00185 /*
00186  * Cliff sensors
00187  * Check each sensor separately
00188  */
00189 void GazeboRosKobuki::updateCliffSensor()
00190 {
00191   // Left cliff sensor
00192   if ((cliff_detected_left_ == false) &&
00193       (cliff_sensor_left_->GetRange(0) >= cliff_detection_threshold_))
00194   {
00195     cliff_detected_left_ = true;
00196     cliff_event_.sensor = kobuki_msgs::CliffEvent::LEFT;
00197     cliff_event_.state = kobuki_msgs::CliffEvent::CLIFF;
00198     // convert distance back to an AD reading
00199     cliff_event_.bottom = (int)(76123.0f * atan2(0.995f, cliff_sensor_left_->GetRange(0)));
00200     cliff_event_pub_.publish(cliff_event_);
00201   }
00202   else if ((cliff_detected_left_ == true) &&
00203             (cliff_sensor_left_->GetRange(0) < cliff_detection_threshold_))
00204   {
00205     cliff_detected_left_ = false;
00206     cliff_event_.sensor = kobuki_msgs::CliffEvent::LEFT;
00207     cliff_event_.state = kobuki_msgs::CliffEvent::FLOOR;
00208     // convert distance back to an AD reading
00209     cliff_event_.bottom = (int)(76123.0f * atan2(0.995f, cliff_sensor_left_->GetRange(0)));
00210     cliff_event_pub_.publish(cliff_event_);
00211   }
00212   // Centre cliff sensor
00213   if ((cliff_detected_center_ == false) &&
00214       (cliff_sensor_center_->GetRange(0) >= cliff_detection_threshold_))
00215   {
00216     cliff_detected_center_ = true;
00217     cliff_event_.sensor = kobuki_msgs::CliffEvent::CENTER;
00218     cliff_event_.state = kobuki_msgs::CliffEvent::CLIFF;
00219     // convert distance back to an AD reading
00220     cliff_event_.bottom = (int)(76123.0f * atan2(0.995f, cliff_sensor_center_->GetRange(0)));
00221     cliff_event_pub_.publish(cliff_event_);
00222   }
00223   else if ((cliff_detected_center_ == true) &&
00224             (cliff_sensor_center_->GetRange(0) < cliff_detection_threshold_))
00225   {
00226     cliff_detected_center_ = false;
00227     cliff_event_.sensor = kobuki_msgs::CliffEvent::CENTER;
00228     cliff_event_.state = kobuki_msgs::CliffEvent::FLOOR;
00229     // convert distance back to an AD reading
00230     cliff_event_.bottom = (int)(76123.0f * atan2(0.995f, cliff_sensor_center_->GetRange(0)));
00231     cliff_event_pub_.publish(cliff_event_);
00232   }
00233   // Right cliff sensor
00234   if ((cliff_detected_right_ == false) &&
00235       (cliff_sensor_right_->GetRange(0) >= cliff_detection_threshold_))
00236   {
00237     cliff_detected_right_ = true;
00238     cliff_event_.sensor = kobuki_msgs::CliffEvent::RIGHT;
00239     cliff_event_.state = kobuki_msgs::CliffEvent::CLIFF;
00240     // convert distance back to an AD reading
00241     cliff_event_.bottom = (int)(76123.0f * atan2(0.995f, cliff_sensor_right_->GetRange(0)));
00242     cliff_event_pub_.publish(cliff_event_);
00243   }
00244   else if ((cliff_detected_right_ == true) &&
00245             (cliff_sensor_right_->GetRange(0) < cliff_detection_threshold_))
00246   {
00247     cliff_detected_right_ = false;
00248     cliff_event_.sensor = kobuki_msgs::CliffEvent::RIGHT;
00249     cliff_event_.state = kobuki_msgs::CliffEvent::FLOOR;
00250     // convert distance back to an AD reading
00251     cliff_event_.bottom = (int)(76123.0f * atan2(0.995f, cliff_sensor_right_->GetRange(0)));
00252     cliff_event_pub_.publish(cliff_event_);
00253   }
00254 }
00255 
00256 /*
00257  * Bumpers
00258  */
00259 // In order to simulate the three bumper sensors, a contact is assigned to one of the bumpers
00260 // depending on its position. Each sensor covers a range of 60 degrees.
00261 // +90 ... +30: left bumper
00262 // +30 ... -30: centre bumper
00263 // -30 ... -90: right bumper
00264 void GazeboRosKobuki::updateBumper()
00265 {
00266   // reset flags
00267   bumper_left_is_pressed_ = false;
00268   bumper_center_is_pressed_ = false;
00269   bumper_right_is_pressed_ = false;
00270                                                                                                                         
00271   // parse contacts
00272   msgs::Contacts contacts;
00273   contacts = bumper_->GetContacts();
00274   math::Pose current_pose = model_->GetWorldPose();
00275   double robot_heading = current_pose.rot.GetYaw();
00276                                                                                                                         
00277   for (int i = 0; i < contacts.contact_size(); ++i)
00278   {
00279     double rel_contact_pos =  contacts.contact(i).position(0).z() - current_pose.pos.z;
00280     // Actually, only contacts at the height of the bumper should be considered, but since we use a simplified collision model
00281     // contacts further below and above need to be consider as well to identify "bumps" reliably.
00282     if ((rel_contact_pos >= 0.01)
00283         && (rel_contact_pos <= 0.13))
00284     {
00285       // using the force normals below, since the contact position is given in world coordinates
00286       // also negating the normal, because it points from contact to robot centre
00287       double global_contact_angle = std::atan2(-contacts.contact(i).normal(0).y(), -contacts.contact(i).normal(0).x());
00288       double relative_contact_angle = global_contact_angle - robot_heading;
00289                                                                                                                         
00290       if ((relative_contact_angle <= (M_PI/2)) && (relative_contact_angle > (M_PI/6)))
00291       {
00292         bumper_left_is_pressed_ = true;
00293       }
00294       else if ((relative_contact_angle <= (M_PI/6)) && (relative_contact_angle >= (-M_PI/6)))
00295       {
00296         bumper_center_is_pressed_ = true;
00297       }
00298       else if ((relative_contact_angle < (-M_PI/6)) && (relative_contact_angle >= (-M_PI/2)))
00299       {
00300         bumper_right_is_pressed_ = true;
00301       }
00302     }
00303   }
00304                                                                                                                         
00305   // check for bumper state change
00306   if (bumper_left_is_pressed_ && !bumper_left_was_pressed_)
00307   {
00308     bumper_left_was_pressed_ = true;
00309     bumper_event_.state = kobuki_msgs::BumperEvent::PRESSED;
00310     bumper_event_.bumper = kobuki_msgs::BumperEvent::LEFT;
00311     bumper_event_pub_.publish(bumper_event_);
00312   }
00313   else if (!bumper_left_is_pressed_ && bumper_left_was_pressed_)
00314   {
00315     bumper_left_was_pressed_ = false;
00316     bumper_event_.state = kobuki_msgs::BumperEvent::RELEASED;
00317     bumper_event_.bumper = kobuki_msgs::BumperEvent::LEFT;
00318     bumper_event_pub_.publish(bumper_event_);
00319   }
00320   if (bumper_center_is_pressed_ && !bumper_center_was_pressed_)
00321   {
00322     bumper_center_was_pressed_ = true;
00323     bumper_event_.state = kobuki_msgs::BumperEvent::PRESSED;
00324     bumper_event_.bumper = kobuki_msgs::BumperEvent::CENTER;
00325     bumper_event_pub_.publish(bumper_event_);
00326   }
00327   else if (!bumper_center_is_pressed_ && bumper_center_was_pressed_)
00328   {
00329     bumper_center_was_pressed_ = false;
00330     bumper_event_.state = kobuki_msgs::BumperEvent::RELEASED;
00331     bumper_event_.bumper = kobuki_msgs::BumperEvent::CENTER;
00332     bumper_event_pub_.publish(bumper_event_);
00333   }
00334   if (bumper_right_is_pressed_ && !bumper_right_was_pressed_)
00335   {
00336     bumper_right_was_pressed_ = true;
00337     bumper_event_.state = kobuki_msgs::BumperEvent::PRESSED;
00338     bumper_event_.bumper = kobuki_msgs::BumperEvent::RIGHT;
00339     bumper_event_pub_.publish(bumper_event_);
00340   }
00341   else if (!bumper_right_is_pressed_ && bumper_right_was_pressed_)
00342   {
00343     bumper_right_was_pressed_ = false;
00344     bumper_event_.state = kobuki_msgs::BumperEvent::RELEASED;
00345     bumper_event_.bumper = kobuki_msgs::BumperEvent::RIGHT;
00346     bumper_event_pub_.publish(bumper_event_);
00347   }
00348 }
00349 }


kobuki_gazebo_plugins
Author(s): Marcus Liebhardt
autogenerated on Thu Jun 6 2019 19:42:48