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