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")) {
88 if(tf_prefix_.empty())
91 boost::trim_right_if(tf_prefix_,boost::is_any_of(
"/"));
99 if (!
sdf_->HasElement(_tag_name)) {
101 info(), _tag_name, (_default?
"ture":
"false"));
109 if (
sdf_->HasElement(_tag_name)) {
110 std::string value =
sdf_->GetElement(_tag_name)->Get<std::string>();
111 if(boost::iequals(value, std::string(
"true")))
115 else if(boost::iequals(value, std::string(
"false")))
126 info(), _tag_name, (_value?
"ture":
"false"));
130 physics::JointPtr
GazeboRos::getJoint(physics::ModelPtr &_parent,
const char *_tag_name,
const std::string &_joint_default_name) {
131 std::string joint_name;
132 getParameter<std::string>(joint_name, _tag_name, _joint_default_name);
133 physics::JointPtr joint = _parent->GetJoint(joint_name);
138 "%s: couldn't get wheel hinge joint named %s",
139 info() , joint_name.c_str());
148 ROS_FATAL_STREAM(
info() <<
"A ROS node for Gazebo has not been initialized, unable to load plugin. " 149 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
#define ROS_INFO_NAMED(name,...)
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
std::string getPrefixParam(ros::NodeHandle &nh)
#define ROS_WARN_NAMED(name,...)
boost::shared_ptr< ros::NodeHandle > & node()
boost::shared_ptr< ros::NodeHandle > rosnode_
name of the launched node
ROSCPP_DECL bool isInitialized()
physics::JointPtr getJoint(physics::ModelPtr &_parent, const char *_tag_name, const std::string &_joint_default_name)
std::string resolveTF(const std::string &_name)
std::string resolve(const std::string &prefix, const std::string &frame_name)
#define ROS_DEBUG_NAMED(name,...)
std::string tf_prefix_
rosnode
#define ROS_FATAL_STREAM(args)
std::string info_text
prefix for the ros tf plublisher if not set it uses the namespace_
void getParameterBoolean(bool &_value, const char *_tag_name, const bool &_default)
std::string namespace_
name of the plugin class
const char * info() const
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
#define ROSCONSOLE_DEFAULT_NAME
void readCommonParameter()
info text for log messages to identify the node