Go to the documentation of this file.
43 #include <boost/bind.hpp>
79 ROS_FATAL_STREAM_NAMED(
"gazebo_ros_control",
"A ROS node for Gazebo has not been initialized, unable to load plugin. "
80 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
85 if(
sdf_->HasElement(
"robotNamespace"))
95 if (
sdf_->HasElement(
"robotParam"))
105 if(
sdf_->HasElement(
"robotSimType"))
119 #if GAZEBO_MAJOR_VERSION >= 8
126 if(
sdf_->HasElement(
"controlPeriod"))
134 <<
" s) is faster than the gazebo simulation period ("<<gazebo_period<<
" s).");
139 <<
" s) is slower than the gazebo simulation period ("<<gazebo_period<<
" s).");
145 ROS_DEBUG_STREAM_NAMED(
"gazebo_ros_control",
"Control period not found in URDF/SDF, defaulting to Gazebo period of "
155 if (
sdf_->HasElement(
"eStopTopic"))
157 const std::string e_stop_topic =
sdf_->GetElement(
"eStopTopic")->Get<std::string>();
169 ROS_ERROR_NAMED(
"gazebo_ros_control",
"Error parsing URDF in gazebo_ros_control plugin, plugin not active.\n");
178 (
"gazebo_ros_control",
179 "gazebo_ros_control::RobotHWSim"));
187 ROS_FATAL_NAMED(
"gazebo_ros_control",
"Could not initialize robot simulation interface");
198 gazebo::event::Events::ConnectWorldUpdateBegin
204 ROS_FATAL_STREAM_NAMED(
"gazebo_ros_control",
"Failed to create robot simulation interface loader: "<<ex.what());
207 ROS_INFO_NAMED(
"gazebo_ros_control",
"Loaded gazebo_ros_control.");
214 #if GAZEBO_MAJOR_VERSION >= 8
215 gazebo::common::Time gz_time_now =
parent_model_->GetWorld()->SimTime();
217 gazebo::common::Time gz_time_now =
parent_model_->GetWorld()->GetSimTime();
219 ros::Time sim_time_ros(gz_time_now.sec, gz_time_now.nsec);
236 reset_ctrlrs =
false;
248 reset_ctrlrs =
false;
271 std::string urdf_string;
274 while (urdf_string.empty())
276 std::string search_param_name;
280 " URDF in parameter [%s] on the ROS param server.", search_param_name.c_str());
292 std::this_thread::sleep_for(std::chrono::microseconds(100000));
GZ_REGISTER_MODEL_PLUGIN(GazeboRosControlPlugin)
static bool parse(const std::string &urdf_string, std::vector< TransmissionInfo > &transmissions)
boost::shared_ptr< controller_manager::ControllerManager > controller_manager_
#define ROS_DEBUG_STREAM_NAMED(name, args)
virtual ~GazeboRosControlPlugin()
bool getParam(const std::string &key, bool &b) const
#define ROS_INFO_ONCE_NAMED(name,...)
virtual void Load(gazebo::physics::ModelPtr parent, sdf::ElementPtr sdf)
ros::NodeHandle model_nh_
#define ROS_ERROR_NAMED(name,...)
bool parseTransmissionsFromURDF(const std::string &urdf_string)
ros::Duration control_period_
#define ROS_FATAL_NAMED(name,...)
ros::Time last_write_sim_time_ros_
#define ROS_INFO_NAMED(name,...)
#define ROS_FATAL_STREAM_NAMED(name, args)
Plugin template for hardware interfaces for ros_control and Gazebo.
void eStopCB(const std_msgs::BoolConstPtr &e_stop_active)
#define ROS_ERROR_STREAM_NAMED(name, args)
ros::Time last_update_sim_time_ros_
std::string robot_hw_sim_type_str_
bool searchParam(const std::string &key, std::string &result) const
ROSCPP_DECL bool isInitialized()
gazebo::physics::ModelPtr parent_model_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
std::string robot_description_
URDF_EXPORT bool initString(const std::string &xmlstring)
std::string robot_namespace_
std::vector< transmission_interface::TransmissionInfo > transmissions_
#define ROS_WARN_STREAM_NAMED(name, args)
boost::shared_ptr< gazebo_ros_control::RobotHWSim > robot_hw_sim_
boost::shared_ptr< pluginlib::ClassLoader< gazebo_ros_control::RobotHWSim > > robot_hw_sim_loader_
#define ROS_INFO_STREAM_NAMED(name, args)
ros::Subscriber e_stop_sub_
std::string getURDF(std::string param_name) const
gazebo::event::ConnectionPtr update_connection_
gazebo_ros_control
Author(s): Jonathan Bohren, Dave Coleman
autogenerated on Sun Mar 2 2025 03:49:21