Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043 #include <boost/bind.hpp>
00044
00045 #include <gazebo_ros_control/gazebo_ros_control_plugin.h>
00046 #include <urdf/model.h>
00047
00048 namespace gazebo_ros_control
00049 {
00050
00051 GazeboRosControlPlugin::~GazeboRosControlPlugin()
00052 {
00053
00054 gazebo::event::Events::DisconnectWorldUpdateBegin(update_connection_);
00055 }
00056
00057
00058 void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::ElementPtr sdf)
00059 {
00060 ROS_INFO_STREAM_NAMED("gazebo_ros_control","Loading gazebo_ros_control plugin");
00061
00062
00063
00064 parent_model_ = parent;
00065 sdf_ = sdf;
00066
00067
00068 if (!parent_model_)
00069 {
00070 ROS_ERROR_STREAM_NAMED("loadThread","parent model is NULL");
00071 return;
00072 }
00073
00074
00075 if(!ros::isInitialized())
00076 {
00077 ROS_FATAL_STREAM_NAMED("gazebo_ros_control","A ROS node for Gazebo has not been initialized, unable to load plugin. "
00078 << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00079 return;
00080 }
00081
00082
00083 if(sdf_->HasElement("robotNamespace"))
00084 {
00085 robot_namespace_ = sdf_->GetElement("robotNamespace")->Get<std::string>();
00086 }
00087 else
00088 {
00089 robot_namespace_ = parent_model_->GetName();
00090 }
00091
00092
00093 if (sdf_->HasElement("robotParam"))
00094 {
00095 robot_description_ = sdf_->GetElement("robotParam")->Get<std::string>();
00096 }
00097 else
00098 {
00099 robot_description_ = "robot_description";
00100 }
00101
00102
00103 if(sdf_->HasElement("robotSimType"))
00104 {
00105 robot_hw_sim_type_str_ = sdf_->Get<std::string>("robotSimType");
00106 }
00107 else
00108 {
00109 robot_hw_sim_type_str_ = "gazebo_ros_control/DefaultRobotHWSim";
00110 ROS_DEBUG_STREAM_NAMED("loadThread","Using default plugin for RobotHWSim (none specified in URDF/SDF)\""<<robot_hw_sim_type_str_<<"\"");
00111 }
00112
00113
00114 ros::Duration gazebo_period(parent_model_->GetWorld()->GetPhysicsEngine()->GetMaxStepSize());
00115
00116
00117 if(sdf_->HasElement("controlPeriod"))
00118 {
00119 control_period_ = ros::Duration(sdf_->Get<double>("controlPeriod"));
00120
00121
00122 if( control_period_ < gazebo_period )
00123 {
00124 ROS_ERROR_STREAM_NAMED("gazebo_ros_control","Desired controller update period ("<<control_period_
00125 <<" s) is faster than the gazebo simulation period ("<<gazebo_period<<" s).");
00126 }
00127 else if( control_period_ > gazebo_period )
00128 {
00129 ROS_WARN_STREAM_NAMED("gazebo_ros_control","Desired controller update period ("<<control_period_
00130 <<" s) is slower than the gazebo simulation period ("<<gazebo_period<<" s).");
00131 }
00132 }
00133 else
00134 {
00135 control_period_ = gazebo_period;
00136 ROS_DEBUG_STREAM_NAMED("gazebo_ros_control","Control period not found in URDF/SDF, defaulting to Gazebo period of "
00137 << control_period_);
00138 }
00139
00140
00141
00142 model_nh_ = ros::NodeHandle(robot_namespace_);
00143 ROS_INFO_NAMED("gazebo_ros_control", "Starting gazebo_ros_control plugin in namespace: %s", robot_namespace_.c_str());
00144
00145
00146
00147
00148 const std::string urdf_string = getURDF(robot_description_);
00149 if (!parseTransmissionsFromURDF(urdf_string))
00150 {
00151 ROS_ERROR_NAMED("gazebo_ros_control", "Error parsing URDF in gazebo_ros_control plugin, plugin not active.\n");
00152 return;
00153 }
00154
00155
00156 try
00157 {
00158 robot_hw_sim_loader_.reset
00159 (new pluginlib::ClassLoader<gazebo_ros_control::RobotHWSim>
00160 ("gazebo_ros_control",
00161 "gazebo_ros_control::RobotHWSim"));
00162
00163 robot_hw_sim_ = robot_hw_sim_loader_->createInstance(robot_hw_sim_type_str_);
00164 urdf::Model urdf_model;
00165 const urdf::Model *const urdf_model_ptr = urdf_model.initString(urdf_string) ? &urdf_model : NULL;
00166
00167 if(!robot_hw_sim_->initSim(robot_namespace_, model_nh_, parent_model_, urdf_model_ptr, transmissions_))
00168 {
00169 ROS_FATAL_NAMED("gazebo_ros_control","Could not initialize robot simulation interface");
00170 return;
00171 }
00172
00173
00174 ROS_DEBUG_STREAM_NAMED("ros_control_plugin","Loading controller_manager");
00175 controller_manager_.reset
00176 (new controller_manager::ControllerManager(robot_hw_sim_.get(), model_nh_));
00177
00178
00179 update_connection_ =
00180 gazebo::event::Events::ConnectWorldUpdateBegin
00181 (boost::bind(&GazeboRosControlPlugin::Update, this));
00182
00183 }
00184 catch(pluginlib::LibraryLoadException &ex)
00185 {
00186 ROS_FATAL_STREAM_NAMED("gazebo_ros_control","Failed to create robot simulation interface loader: "<<ex.what());
00187 }
00188
00189 ROS_INFO_NAMED("gazebo_ros_control", "Loaded gazebo_ros_control.");
00190 }
00191
00192
00193 void GazeboRosControlPlugin::Update()
00194 {
00195
00196 gazebo::common::Time gz_time_now = parent_model_->GetWorld()->GetSimTime();
00197 ros::Time sim_time_ros(gz_time_now.sec, gz_time_now.nsec);
00198 ros::Duration sim_period = sim_time_ros - last_update_sim_time_ros_;
00199
00200
00201 if(sim_period >= control_period_) {
00202
00203 last_update_sim_time_ros_ = sim_time_ros;
00204
00205
00206 robot_hw_sim_->readSim(sim_time_ros, sim_period);
00207
00208
00209 controller_manager_->update(sim_time_ros, sim_period);
00210 }
00211
00212
00213
00214 robot_hw_sim_->writeSim(sim_time_ros, sim_time_ros - last_write_sim_time_ros_);
00215 last_write_sim_time_ros_ = sim_time_ros;
00216 }
00217
00218
00219 void GazeboRosControlPlugin::Reset()
00220 {
00221
00222 last_update_sim_time_ros_ = ros::Time();
00223 last_write_sim_time_ros_ = ros::Time();
00224 }
00225
00226
00227 std::string GazeboRosControlPlugin::getURDF(std::string param_name) const
00228 {
00229 std::string urdf_string;
00230
00231
00232 while (urdf_string.empty())
00233 {
00234 std::string search_param_name;
00235 if (model_nh_.searchParam(param_name, search_param_name))
00236 {
00237 ROS_INFO_ONCE_NAMED("gazebo_ros_control", "gazebo_ros_control plugin is waiting for model"
00238 " URDF in parameter [%s] on the ROS param server.", search_param_name.c_str());
00239
00240 model_nh_.getParam(search_param_name, urdf_string);
00241 }
00242 else
00243 {
00244 ROS_INFO_ONCE_NAMED("gazebo_ros_control", "gazebo_ros_control plugin is waiting for model"
00245 " URDF in parameter [%s] on the ROS param server.", robot_description_.c_str());
00246
00247 model_nh_.getParam(param_name, urdf_string);
00248 }
00249
00250 usleep(100000);
00251 }
00252 ROS_DEBUG_STREAM_NAMED("gazebo_ros_control", "Recieved urdf from param server, parsing...");
00253
00254 return urdf_string;
00255 }
00256
00257
00258 bool GazeboRosControlPlugin::parseTransmissionsFromURDF(const std::string& urdf_string)
00259 {
00260 transmission_interface::TransmissionParser::parse(urdf_string, transmissions_);
00261 return true;
00262 }
00263
00264
00265
00266 GZ_REGISTER_MODEL_PLUGIN(GazeboRosControlPlugin);
00267 }