gazebo_ros_kobuki.cpp
Go to the documentation of this file.
00001 
00002 #include <cmath>
00003 #include <cstring>
00004 #include <boost/bind.hpp>
00005 #include <sensor_msgs/JointState.h>
00006 #include <tf/LinearMath/Quaternion.h>
00007 #include <gazebo/math/gzmath.hh>
00008 #include "kobuki_gazebo_plugins/gazebo_ros_kobuki.h"
00009 
00010 namespace gazebo
00011 {
00012 
00013 
00014 GazeboRosKobuki::GazeboRosKobuki() : shutdown_requested_(false)
00015 {
00016   // Initialise variables
00017   wheel_speed_cmd_[LEFT] = 0.0;
00018   wheel_speed_cmd_[RIGHT] = 0.0;
00019   cliff_detected_left_ = false;
00020   cliff_detected_center_ = false;
00021   cliff_detected_right_ = false;
00022 }
00023 
00024 GazeboRosKobuki::~GazeboRosKobuki()
00025 {
00026 //  rosnode_->shutdown();
00027   shutdown_requested_ = true;
00028   // Wait for spinner thread to end
00029 //  ros_spinner_thread_->join();
00030 
00031   //  delete spinner_thread_;
00032 //  delete rosnode_;
00033 }
00034 
00035 void GazeboRosKobuki::Load(physics::ModelPtr parent, sdf::ElementPtr sdf)
00036 {
00037   model_ = parent;
00038   if (!model_)
00039   {
00040     ROS_ERROR_STREAM("Invalid model pointer! [" << node_name_ << "]");
00041     return;
00042   }
00043  
00044   gazebo_ros_ = GazeboRosPtr(new GazeboRos(model_, sdf, "Kobuki"));
00045   sdf_ = sdf;
00046  
00047   // Make sure the ROS node for Gazebo has already been initialized
00048   if (!ros::isInitialized())
00049   {
00050     ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
00051       << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00052     return;
00053   }
00054  
00055   // Get then name of the parent model and use it as node name
00056   std::string model_name = sdf->GetParent()->Get<std::string>("name");
00057   gzdbg << "Plugin model name: " << model_name << "\n";
00058   node_name_ = model_name;
00059   world_ = parent->GetWorld();
00060  
00061   prepareMotorPower();
00062   preparePublishTf();
00063 
00064   if(prepareJointState() == false)
00065     return;
00066   if(prepareWheelAndTorque() == false)
00067     return;
00068   
00069   prepareOdom();
00070 
00071   if(prepareVelocityCommand() == false)
00072     return;
00073   if(prepareCliffSensor() == false)
00074     return;
00075   if(prepareBumper() == false)
00076     return;
00077   if(prepareIMU() == false)
00078     return;
00079 
00080   setupRosApi(model_name);
00081 
00082   prev_update_time_ = world_->GetSimTime();
00083   ROS_INFO_STREAM("GazeboRosKobuki plugin ready to go! [" << node_name_ << "]");
00084   update_connection_ = event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosKobuki::OnUpdate, this));
00085 }
00086 
00087 
00088 void GazeboRosKobuki::OnUpdate()
00089 {
00090   /*
00091    * First process ROS callbacks
00092    */
00093   ros::spinOnce();
00094 
00095   /*
00096    * Update current time and time step
00097    */
00098   common::Time time_now = world_->GetSimTime();
00099   common::Time step_time = time_now - prev_update_time_;
00100   prev_update_time_ = time_now;
00101 
00102   updateJointState();
00103   updateOdometry(step_time);
00104   updateIMU();
00105   propagateVelocityCommands();
00106   updateCliffSensor();
00107   updateBumper();
00108 }
00109 
00110 void GazeboRosKobuki::spin()
00111 {
00112   ros::Rate r(10);
00113   while(ros::ok() && !shutdown_requested_)
00114   {
00115     r.sleep();
00116   }
00117 }
00118 
00119 void GazeboRosKobuki::motorPowerCB(const kobuki_msgs::MotorPowerPtr &msg)
00120 {
00121   if ((msg->state == kobuki_msgs::MotorPower::ON) && (!motors_enabled_))
00122   {
00123     motors_enabled_ = true;
00124     ROS_INFO_STREAM("Motors fired up. [" << node_name_ << "]");
00125   }
00126   else if ((msg->state == kobuki_msgs::MotorPower::OFF) && (motors_enabled_))
00127   {
00128     motors_enabled_ = false;
00129     ROS_INFO_STREAM("Motors taking a rest. [" << node_name_ << "]");
00130   }
00131 }
00132 
00133 void GazeboRosKobuki::cmdVelCB(const geometry_msgs::TwistConstPtr &msg)
00134 {
00135   last_cmd_vel_time_ = world_->GetSimTime();
00136   wheel_speed_cmd_[LEFT] = msg->linear.x - msg->angular.z * (wheel_sep_) / 2;
00137   wheel_speed_cmd_[RIGHT] = msg->linear.x + msg->angular.z * (wheel_sep_) / 2;
00138 }
00139 
00140 void GazeboRosKobuki::resetOdomCB(const std_msgs::EmptyConstPtr &msg)
00141 {
00142   odom_pose_[0] = 0.0;
00143   odom_pose_[1] = 0.0;
00144   odom_pose_[2] = 0.0;
00145 }
00146 
00147 // Register this plugin with the simulator
00148 GZ_REGISTER_MODEL_PLUGIN(GazeboRosKobuki);
00149 
00150 } // namespace gazebo


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