59 std::string debugLevel;
60 getParameter<std::string>(debugLevel,
"rosDebugLevel",
"na");
61 if(boost::iequals(debugLevel, std::string(
"Debug"))) {
65 }
else if(boost::iequals(debugLevel, std::string(
"Info"))) {
69 }
else if(boost::iequals(debugLevel, std::string(
"Warn"))) {
73 }
else if(boost::iequals(debugLevel, std::string(
"Error"))) {
77 }
else if(boost::iequals(debugLevel, std::string(
"Fatal"))) {
82 if (
sdf_->HasElement(
"rosDebugLevel")) {
94 if (!
sdf_->HasElement(_tag_name)) {
96 info(), _tag_name, (_default?
"true":
"false"));
104 if (
sdf_->HasElement(_tag_name)) {
105 std::string value =
sdf_->GetElement(_tag_name)->Get<std::string>();
106 if(boost::iequals(value, std::string(
"true")) || boost::iequals(value, std::string(
"1")))
110 else if(boost::iequals(value, std::string(
"false")) || boost::iequals(value, std::string(
"0")))
116 ROS_WARN_NAMED(
"utils",
"%s: <%s> must be either true or false but is '%s'",
117 info(), _tag_name, value.c_str());
121 info(), _tag_name, (_value?
"true":
"false"));
125 physics::JointPtr
GazeboRos::getJoint(physics::ModelPtr &_parent,
const char *_tag_name,
const std::string &_joint_default_name) {
126 std::string joint_name;
127 getParameter<std::string>(joint_name, _tag_name, _joint_default_name);
128 physics::JointPtr joint = _parent->GetJoint(joint_name);
133 "%s: couldn't get wheel hinge joint named %s",
134 info() , joint_name.c_str());
143 ROS_FATAL_STREAM(
info() <<
"A ROS node for Gazebo has not been initialized, unable to load plugin. "
144 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");