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


turtlebot_gazebo_plugins
Author(s): Nate Koenig
autogenerated on Tue Dec 10 2013 15:49:43