gazebo_ros_create.cpp
Go to the documentation of this file.
00001 #include <gazebo/sensors/SensorManager.hh>
00002 #include <gazebo/sensors/RaySensor.hh>
00003 #include <create_node/TurtlebotSensorState.h>
00004 #include <nav_msgs/Odometry.h>
00005 #include <geometry_msgs/Twist.h>
00006 #include <sensor_msgs/JointState.h>
00007 #include "turtlebot_plugins/gazebo_ros_create.h"
00008 
00009 using namespace gazebo;
00010 
00011 enum {LEFT= 0, RIGHT=1, FRONT=2, REAR=3};
00012 
00013 GazeboRosCreate::GazeboRosCreate()
00014 {
00015   this->spinner_thread_ = new boost::thread( boost::bind( &GazeboRosCreate::spin, this) );
00016 
00017   wheel_speed_ = new float[2];
00018   wheel_speed_[LEFT] = 0.0;
00019   wheel_speed_[RIGHT] = 0.0;
00020 
00021   set_joints_[0] = false;
00022   set_joints_[1] = false;
00023   set_joints_[2] = false;
00024   set_joints_[3] = false;
00025   joints_[0].reset();
00026   joints_[1].reset();
00027   joints_[2].reset();
00028   joints_[3].reset();
00029 }
00030 
00031 GazeboRosCreate::~GazeboRosCreate()
00032 {
00033   rosnode_->shutdown();
00034   this->spinner_thread_->join();
00035   delete this->spinner_thread_;
00036   delete [] wheel_speed_;
00037   delete rosnode_;
00038 }
00039     
00040 void GazeboRosCreate::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf )
00041 {
00042   this->my_world_ = _parent->GetWorld();
00043 
00044   this->my_parent_ = _parent;
00045   if (!this->my_parent_)
00046   {
00047     ROS_FATAL("Gazebo_ROS_Create controller requires a Model as its parent");
00048     return;
00049   }
00050 
00051 
00052   this->node_namespace_ = "";
00053   if (_sdf->HasElement("node_namespace"))
00054     this->node_namespace_ = _sdf->GetElement("node_namespace")->Get<std::string>() + "/";
00055 
00056 
00057   left_wheel_joint_name_ = "left_wheel_joint";
00058   if (_sdf->HasElement("left_wheel_joint"))
00059     left_wheel_joint_name_ = _sdf->GetElement("left_wheel_joint")->Get<std::string>();
00060 
00061   right_wheel_joint_name_ = "right_wheel_joint";
00062   if (_sdf->HasElement("right_wheel_joint"))
00063     right_wheel_joint_name_ = _sdf->GetElement("right_wheel_joint")->Get<std::string>();
00064 
00065   front_castor_joint_name_ = "front_castor_joint";
00066   if (_sdf->HasElement("front_castor_joint"))
00067     front_castor_joint_name_ = _sdf->GetElement("front_castor_joint")->Get<std::string>();
00068 
00069   rear_castor_joint_name_ = "rear_castor_joint";
00070   if (_sdf->HasElement("rear_castor_joint"))
00071     rear_castor_joint_name_ = _sdf->GetElement("rear_castor_joint")->Get<std::string>();
00072 
00073   wheel_sep_ = 0.34;
00074   if (_sdf->HasElement("wheel_separation"))
00075     wheel_sep_ = _sdf->GetElement("wheel_separation")->Get<double>();
00076 
00077   wheel_sep_ = 0.34;
00078   if (_sdf->HasElement("wheel_separation"))
00079     wheel_sep_ = _sdf->GetElement("wheel_separation")->Get<double>();
00080 
00081   wheel_diam_ = 0.15;
00082   if (_sdf->HasElement("wheel_diameter"))
00083     wheel_diam_ = _sdf->GetElement("wheel_diameter")->Get<double>();
00084 
00085   torque_ = 10.0;
00086   if (_sdf->HasElement("torque"))
00087     torque_ = _sdf->GetElement("torque")->Get<double>();
00088 
00089   base_geom_name_ = "base_footprint_collision_base_link";
00090   if (_sdf->HasElement("base_geom"))
00091     base_geom_name_ = _sdf->GetElement("base_geom")->Get<std::string>();
00092   base_geom_ = my_parent_->GetChildCollision(base_geom_name_);
00093   if (!base_geom_)
00094   {
00095     // This is a hack for ROS Diamond back. E-turtle and future releases
00096     // will not need this, because it will contain the fixed-joint reduction
00097     // in urdf2gazebo
00098     base_geom_ = my_parent_->GetChildCollision("base_footprint_geom");
00099     if (!base_geom_)
00100     {
00101       ROS_ERROR("Unable to find geom[%s]",base_geom_name_.c_str());
00102       return;
00103     }
00104   }
00105 
00106   base_geom_->SetContactsEnabled(true);
00107   contact_event_ = base_geom_->ConnectContact(boost::bind(&GazeboRosCreate::OnContact, this, _1, _2));
00108 
00109   wall_sensor_ = boost::dynamic_pointer_cast<sensors::RaySensor>(
00110     sensors::SensorManager::Instance()->GetSensor("wall_sensor"));
00111   if (!wall_sensor_)
00112   {
00113     ROS_ERROR("Unable to find sensor[wall_sensor]");
00114     return;
00115   }
00116 
00117   left_cliff_sensor_ = boost::dynamic_pointer_cast<sensors::RaySensor>(
00118     sensors::SensorManager::Instance()->GetSensor("left_cliff_sensor"));
00119   right_cliff_sensor_ = boost::dynamic_pointer_cast<sensors::RaySensor>(
00120     sensors::SensorManager::Instance()->GetSensor("right_cliff_sensor"));
00121   leftfront_cliff_sensor_ = boost::dynamic_pointer_cast<sensors::RaySensor>(
00122     sensors::SensorManager::Instance()->GetSensor("leftfront_cliff_sensor"));
00123   rightfront_cliff_sensor_ = boost::dynamic_pointer_cast<sensors::RaySensor>(
00124     sensors::SensorManager::Instance()->GetSensor("rightfront_cliff_sensor"));
00125 
00126   wall_sensor_->SetActive(true);
00127   left_cliff_sensor_->SetActive(true);
00128   right_cliff_sensor_->SetActive(true);
00129   rightfront_cliff_sensor_->SetActive(true);
00130   leftfront_cliff_sensor_->SetActive(true);
00131 
00132   if (!ros::isInitialized())
00133   {
00134     int argc = 0;
00135     char** argv = NULL;
00136     ros::init(argc, argv, "gazebo_turtlebot", ros::init_options::NoSigintHandler|ros::init_options::AnonymousName);
00137   }
00138 
00139   rosnode_ = new ros::NodeHandle( node_namespace_ );
00140 
00141   cmd_vel_sub_ = rosnode_->subscribe("cmd_vel", 1, &GazeboRosCreate::OnCmdVel, this );
00142 
00143   sensor_state_pub_ = rosnode_->advertise<create_node::TurtlebotSensorState>("sensor_state", 1);
00144   odom_pub_ = rosnode_->advertise<nav_msgs::Odometry>("/odom", 1);
00145 
00146   joint_state_pub_ = rosnode_->advertise<sensor_msgs::JointState>("/joint_states", 1);
00147 
00148   js_.name.push_back( left_wheel_joint_name_ );
00149   js_.position.push_back(0);
00150   js_.velocity.push_back(0);
00151   js_.effort.push_back(0);
00152 
00153   js_.name.push_back( right_wheel_joint_name_ );
00154   js_.position.push_back(0);
00155   js_.velocity.push_back(0);
00156   js_.effort.push_back(0);
00157 
00158   js_.name.push_back( front_castor_joint_name_ );
00159   js_.position.push_back(0);
00160   js_.velocity.push_back(0);
00161   js_.effort.push_back(0);
00162 
00163   js_.name.push_back( rear_castor_joint_name_ );
00164   js_.position.push_back(0);
00165   js_.velocity.push_back(0);
00166   js_.effort.push_back(0);
00167 
00168   prev_update_time_ = 0;
00169   last_cmd_vel_time_ = 0;
00170 
00171 
00172   sensor_state_.bumps_wheeldrops = 0x0;
00173 
00174   //TODO: fix this
00175 
00176   joints_[LEFT] = my_parent_->GetJoint(left_wheel_joint_name_);
00177   joints_[RIGHT] = my_parent_->GetJoint(right_wheel_joint_name_);
00178   joints_[FRONT] = my_parent_->GetJoint(front_castor_joint_name_);
00179   joints_[REAR] = my_parent_->GetJoint(rear_castor_joint_name_);
00180 
00181   if (joints_[LEFT]) set_joints_[LEFT] = true;
00182   if (joints_[RIGHT]) set_joints_[RIGHT] = true;
00183   if (joints_[FRONT]) set_joints_[FRONT] = true;
00184   if (joints_[REAR]) set_joints_[REAR] = true;
00185 
00186   //initialize time and odometry position
00187   prev_update_time_ = last_cmd_vel_time_ = this->my_world_->GetSimTime();
00188   odom_pose_[0] = 0.0;
00189   odom_pose_[1] = 0.0;
00190   odom_pose_[2] = 0.0;
00191 
00192   // Get then name of the parent model
00193   std::string modelName = _sdf->GetParent()->Get<std::string>("name");
00194 
00195   // Listen to the update event. This event is broadcast every
00196   // simulation iteration.
00197   this->updateConnection = event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosCreate::UpdateChild, this));
00198   gzdbg << "plugin model name: " << modelName << "\n";
00199 }
00200 
00201 
00202 void GazeboRosCreate::OnContact(const std::string &name, const physics::Contact &contact)
00203 {
00204   float y_overlap = 0.16495 * sin( 10 * (M_PI/180.0) );
00205 
00206   for (unsigned int j=0; j < (unsigned int)contact.count; j++)
00207   {
00208     // Make sure the contact is on the front bumper
00209     if (contact.positions[j].x > 0.012 && contact.positions[j].z < 0.06 && 
00210         contact.positions[j].z > 0.01)
00211     {
00212       // Right bump sensor
00213       if (contact.positions[j].y <= y_overlap)
00214         sensor_state_.bumps_wheeldrops |= 0x1; 
00215       // Left bump sensor
00216       if (contact.positions[j].y >= -y_overlap)
00217         sensor_state_.bumps_wheeldrops |= 0x2; 
00218     }
00219   }
00220 
00221 }
00222 
00223 void GazeboRosCreate::UpdateChild()
00224 {
00225   common::Time time_now = this->my_world_->GetSimTime();
00226   common::Time step_time = time_now - prev_update_time_;
00227   prev_update_time_ = time_now;
00228 
00229   double wd, ws;
00230   double d1, d2;
00231   double dr, da;
00232 
00233   wd = wheel_diam_;
00234   ws = wheel_sep_;
00235 
00236   d1 = d2 = 0;
00237   dr = da = 0;
00238 
00239   // Distance travelled by front wheels
00240   if (set_joints_[LEFT])
00241     d1 = step_time.Double() * (wd / 2) * joints_[LEFT]->GetVelocity(0);
00242   if (set_joints_[RIGHT])
00243     d2 = step_time.Double() * (wd / 2) * joints_[RIGHT]->GetVelocity(0);
00244 
00245   // Can see NaN values here, just zero them out if needed
00246   if (isnan(d1)) {
00247     ROS_WARN_THROTTLE(0.1, "Gazebo ROS Create plugin. NaN in d1. Step time: %.2f. WD: %.2f. Velocity: %.2f", step_time.Double(), wd, joints_[LEFT]->GetVelocity(0));
00248     d1 = 0;
00249   }
00250 
00251   if (isnan(d2)) {
00252     ROS_WARN_THROTTLE(0.1, "Gazebo ROS Create plugin. NaN in d2. Step time: %.2f. WD: %.2f. Velocity: %.2f", step_time.Double(), wd, joints_[RIGHT]->GetVelocity(0));
00253     d2 = 0;
00254   }
00255 
00256   dr = (d1 + d2) / 2;
00257   da = (d2 - d1) / ws;
00258 
00259   // Compute odometric pose
00260   odom_pose_[0] += dr * cos( odom_pose_[2] );
00261   odom_pose_[1] += dr * sin( odom_pose_[2] );
00262   odom_pose_[2] += da;
00263 
00264   // Compute odometric instantaneous velocity
00265   odom_vel_[0] = dr / step_time.Double();
00266   odom_vel_[1] = 0.0;
00267   odom_vel_[2] = da / step_time.Double();
00268 
00269 
00270   if (set_joints_[LEFT])
00271   {
00272     joints_[LEFT]->SetVelocity( 0, wheel_speed_[LEFT] / (wd/2.0) );
00273     joints_[LEFT]->SetMaxForce( 0, torque_ );
00274   }
00275   if (set_joints_[RIGHT])
00276   {
00277     joints_[RIGHT]->SetVelocity( 0, wheel_speed_[RIGHT] / (wd / 2.0) );
00278     joints_[RIGHT]->SetMaxForce( 0, torque_ );
00279   }
00280 
00281   nav_msgs::Odometry odom;
00282   odom.header.stamp.sec = time_now.sec;
00283   odom.header.stamp.nsec = time_now.nsec;
00284   odom.header.frame_id = "odom";
00285   odom.child_frame_id = "base_footprint";
00286   odom.pose.pose.position.x = odom_pose_[0];
00287   odom.pose.pose.position.y = odom_pose_[1];
00288   odom.pose.pose.position.z = 0;
00289 
00290   tf::Quaternion qt;
00291   qt.setEuler(0,0,odom_pose_[2]);
00292 
00293   odom.pose.pose.orientation.x = qt.getX();
00294   odom.pose.pose.orientation.y = qt.getY();
00295   odom.pose.pose.orientation.z = qt.getZ();
00296   odom.pose.pose.orientation.w = qt.getW();
00297 
00298   double pose_cov[36] = { 1e-3, 0, 0, 0, 0, 0,
00299                           0, 1e-3, 0, 0, 0, 0,
00300                           0, 0, 1e6, 0, 0, 0,
00301                           0, 0, 0, 1e6, 0, 0,
00302                           0, 0, 0, 0, 1e6, 0,
00303                           0, 0, 0, 0, 0, 1e3};
00304 
00305   memcpy( &odom.pose.covariance[0], pose_cov, sizeof(double)*36 );
00306   memcpy( &odom.twist.covariance[0], pose_cov, sizeof(double)*36 );
00307 
00308   odom.twist.twist.linear.x = 0;
00309   odom.twist.twist.linear.y = 0;
00310   odom.twist.twist.linear.z = 0;
00311 
00312   odom.twist.twist.angular.x = 0;
00313   odom.twist.twist.angular.y = 0;
00314   odom.twist.twist.angular.z = 0;
00315 
00316   odom_pub_.publish( odom ); 
00317 
00318   js_.header.stamp.sec = time_now.sec;
00319   js_.header.stamp.nsec = time_now.nsec;
00320   if (this->set_joints_[LEFT])
00321   {
00322     js_.position[0] = joints_[LEFT]->GetAngle(0).Radian();
00323     js_.velocity[0] = joints_[LEFT]->GetVelocity(0);
00324   }
00325 
00326   if (this->set_joints_[RIGHT])
00327   {
00328     js_.position[1] = joints_[RIGHT]->GetAngle(0).Radian();
00329     js_.velocity[1] = joints_[RIGHT]->GetVelocity(0);
00330   }
00331 
00332   if (this->set_joints_[FRONT])
00333   {
00334     js_.position[2] = joints_[FRONT]->GetAngle(0).Radian();
00335     js_.velocity[2] = joints_[FRONT]->GetVelocity(0);
00336   }
00337 
00338   if (this->set_joints_[REAR])
00339   {
00340     js_.position[3] = joints_[REAR]->GetAngle(0).Radian();
00341     js_.velocity[3] = joints_[REAR]->GetVelocity(0);
00342   }
00343 
00344   joint_state_pub_.publish( js_ );
00345 
00346   this->UpdateSensors();
00347 
00348   //timeout if didn't receive cmd in a while
00349   common::Time time_since_last_cmd = time_now - last_cmd_vel_time_;
00350   if (time_since_last_cmd.Double() > 0.6)
00351   {
00352     wheel_speed_[LEFT] = 0;
00353     wheel_speed_[RIGHT] = 0;
00354   }
00355 
00356 }
00357 
00358 void GazeboRosCreate::UpdateSensors()
00359 {
00360   if (wall_sensor_->GetRange(0) < 0.04)
00361     sensor_state_.wall = true;
00362   else
00363     sensor_state_.wall = false;
00364 
00365   if (left_cliff_sensor_->GetRange(0) > 0.02)
00366     sensor_state_.cliff_left = true;
00367   else
00368     sensor_state_.cliff_left = false;
00369 
00370   if (right_cliff_sensor_->GetRange(0) > 0.02)
00371     sensor_state_.cliff_right = true;
00372   else
00373     sensor_state_.cliff_right = false;
00374 
00375   if (rightfront_cliff_sensor_->GetRange(0) > 0.02)
00376     sensor_state_.cliff_front_right = true;
00377   else
00378     sensor_state_.cliff_front_right = false;
00379 
00380   if (leftfront_cliff_sensor_->GetRange(0) > 0.02)
00381     sensor_state_.cliff_front_left = true;
00382   else
00383     sensor_state_.cliff_front_left = false;
00384 
00385   sensor_state_pub_.publish(sensor_state_);
00386 
00387   // Reset the bump sensors
00388   sensor_state_.bumps_wheeldrops = 0x0;
00389 }
00390 
00391 void GazeboRosCreate::OnCmdVel( const geometry_msgs::TwistConstPtr &msg)
00392 {
00393   last_cmd_vel_time_ = this->my_world_->GetSimTime();
00394   double vr, va;
00395   vr = msg->linear.x;
00396   va = msg->angular.z;
00397 
00398   wheel_speed_[LEFT] = vr - va * (wheel_sep_) / 2;
00399   wheel_speed_[RIGHT] = vr + va * (wheel_sep_) / 2;
00400 }
00401 
00402 void GazeboRosCreate::spin()
00403 {
00404   while(ros::ok()) ros::spinOnce();
00405 }
00406 
00407 GZ_REGISTER_MODEL_PLUGIN(GazeboRosCreate);
00408 


create_gazebo_plugins
Author(s): Nate Koenig
autogenerated on Thu Aug 27 2015 15:27:14