43 #include <boost/bind.hpp> 77 ROS_FATAL_STREAM_NAMED(
"gazebo_ros_control",
"A ROS node for Gazebo has not been initialized, unable to load plugin. " 78 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
83 if(
sdf_->HasElement(
"robotNamespace"))
93 if (
sdf_->HasElement(
"robotParam"))
103 if(
sdf_->HasElement(
"robotSimType"))
116 if (
sdf_->HasElement(
"legacyModeNS")) {
117 if(
sdf_->GetElement(
"legacyModeNS")->Get<
bool>() ){
122 ROS_ERROR(
"GazeboRosControlPlugin missing <legacyModeNS> while using DefaultRobotHWSim, defaults to true.\n" 123 "This setting assumes you have an old package with an old implementation of DefaultRobotHWSim, " 124 "where the robotNamespace is disregarded and absolute paths are used instead.\n" 125 "If you do not want to fix this issue in an old package just set <legacyModeNS> to true.\n" 131 #if GAZEBO_MAJOR_VERSION >= 8 138 if(
sdf_->HasElement(
"controlPeriod"))
146 <<
" s) is faster than the gazebo simulation period ("<<gazebo_period<<
" s).");
151 <<
" s) is slower than the gazebo simulation period ("<<gazebo_period<<
" s).");
157 ROS_DEBUG_STREAM_NAMED(
"gazebo_ros_control",
"Control period not found in URDF/SDF, defaulting to Gazebo period of " 167 if (
sdf_->HasElement(
"eStopTopic"))
169 const std::string e_stop_topic =
sdf_->GetElement(
"eStopTopic")->Get<std::string>();
181 ROS_ERROR_NAMED(
"gazebo_ros_control",
"Error parsing URDF in gazebo_ros_control plugin, plugin not active.\n");
190 (
"gazebo_ros_control",
191 "gazebo_ros_control::RobotHWSim"));
199 ROS_FATAL_NAMED(
"gazebo_ros_control",
"Could not initialize robot simulation interface");
210 gazebo::event::Events::ConnectWorldUpdateBegin
216 ROS_FATAL_STREAM_NAMED(
"gazebo_ros_control",
"Failed to create robot simulation interface loader: "<<ex.what());
219 ROS_INFO_NAMED(
"gazebo_ros_control",
"Loaded gazebo_ros_control.");
226 #if GAZEBO_MAJOR_VERSION >= 8 227 gazebo::common::Time gz_time_now =
parent_model_->GetWorld()->SimTime();
229 gazebo::common::Time gz_time_now =
parent_model_->GetWorld()->GetSimTime();
231 ros::Time sim_time_ros(gz_time_now.sec, gz_time_now.nsec);
239 last_update_sim_time_ros_ = sim_time_ros;
248 reset_ctrlrs =
false;
260 reset_ctrlrs =
false;
283 std::string urdf_string;
286 while (urdf_string.empty())
288 std::string search_param_name;
292 " URDF in parameter [%s] on the ROS param server.", search_param_name.c_str());
virtual ~GazeboRosControlPlugin()
static bool parse(const std::string &urdf_string, std::vector< TransmissionInfo > &transmissions)
#define ROS_INFO_NAMED(name,...)
ros::NodeHandle model_nh_
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
boost::shared_ptr< controller_manager::ControllerManager > controller_manager_
URDF_EXPORT bool initString(const std::string &xmlstring)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL bool isInitialized()
gazebo::event::ConnectionPtr update_connection_
ros::Subscriber e_stop_sub_
gazebo::physics::ModelPtr parent_model_
#define ROS_INFO_STREAM_NAMED(name, args)
ros::Time last_update_sim_time_ros_
boost::shared_ptr< gazebo_ros_control::RobotHWSim > robot_hw_sim_
bool parseTransmissionsFromURDF(const std::string &urdf_string)
ros::Time last_write_sim_time_ros_
#define ROS_FATAL_STREAM_NAMED(name, args)
bool searchParam(const std::string &key, std::string &result) const
std::vector< transmission_interface::TransmissionInfo > transmissions_
GZ_REGISTER_MODEL_PLUGIN(GazeboRosControlPlugin)
#define ROS_INFO_ONCE_NAMED(name,...)
ros::Duration control_period_
void eStopCB(const std_msgs::BoolConstPtr &e_stop_active)
std::string robot_namespace_
std::string robot_description_
std::string robot_hw_sim_type_str_
bool getParam(const std::string &key, std::string &s) const
boost::shared_ptr< pluginlib::ClassLoader< gazebo_ros_control::RobotHWSim > > robot_hw_sim_loader_
#define ROS_FATAL_NAMED(name,...)
#define ROS_ERROR_NAMED(name,...)
Plugin template for hardware interfaces for ros_control and Gazebo.
virtual void Load(gazebo::physics::ModelPtr parent, sdf::ElementPtr sdf)
std::string getURDF(std::string param_name) const
#define ROS_WARN_STREAM_NAMED(name, args)