Skip to content

Commit

Permalink
Namespace console output (ros-simulation#543)
Browse files Browse the repository at this point in the history
Namespace all console output
  • Loading branch information
davetcoleman committed Feb 16, 2017
1 parent 8de84e2 commit 464c8f8
Show file tree
Hide file tree
Showing 43 changed files with 326 additions and 342 deletions.
23 changes: 10 additions & 13 deletions gazebo_plugins/include/gazebo_plugins/gazebo_ros_utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -87,16 +87,16 @@ inline std::string GetRobotNamespace ( const sensors::SensorPtr &parent, const s
if ( sdf->HasElement ( "robotNamespace" ) ) {
name_space = sdf->Get<std::string> ( "robotNamespace" );
if ( name_space.empty() ) {
ss << "the 'robotNamespace' param was empty";
ss << "The 'robotNamespace' param was empty";
name_space = GetModelName ( parent );
} else {
ss << "Using the 'robotNamespace' param: '" << name_space << "'";
}
} else {
ss << "the 'robotNamespace' param did not exit";
ss << "The 'robotNamespace' param did not exit";
}
if ( pInfo != NULL ) {
ROS_INFO ( "%s Plugin (robotNamespace = %s), Info: %s" , pInfo, name_space.c_str(), ss.str().c_str() );
ROS_INFO_NAMED("utils", "%s Plugin: %s" , pInfo, ss.str().c_str() );
}
return name_space;
}
Expand Down Expand Up @@ -130,7 +130,7 @@ class GazeboRos
: sdf_ ( _sdf ), plugin_ ( _plugin ) {
namespace_ = _parent->GetName ();
if ( !sdf_->HasElement ( "robotNamespace" ) ) {
ROS_INFO ( "%s missing <robotNamespace>, defaults is %s", plugin_.c_str(), namespace_.c_str() );
ROS_INFO_NAMED("utils", "%s missing <robotNamespace>, defaults is %s", plugin_.c_str(), namespace_.c_str() );
} else {
namespace_ = sdf_->GetElement ( "robotNamespace" )->Get<std::string>();
if ( namespace_.empty() ) {
Expand Down Expand Up @@ -165,7 +165,7 @@ class GazeboRos
ss << "the 'robotNamespace' param did not exit";
}
info_text = plugin_ + "(ns = " + namespace_ + ")";
ROS_INFO ( "%s: %s" , info_text.c_str(), ss.str().c_str() );
ROS_INFO_NAMED("utils", "%s: %s" , info_text.c_str(), ss.str().c_str() );
readCommonParameter ();
}

Expand Down Expand Up @@ -232,7 +232,7 @@ class GazeboRos
void getParameter ( T &_value, const char *_tag_name, const T &_default ) {
_value = _default;
if ( !sdf_->HasElement ( _tag_name ) ) {
ROS_WARN ( "%s: missing <%s> default is %s", info(), _tag_name, boost::lexical_cast<std::string> ( _default ).c_str() );
ROS_WARN_NAMED("utils", "%s: missing <%s> default is %s", info(), _tag_name, boost::lexical_cast<std::string> ( _default ).c_str() );
} else {
this->getParameter<T> ( _value, _tag_name );
}
Expand All @@ -249,7 +249,7 @@ class GazeboRos
if ( sdf_->HasElement ( _tag_name ) ) {
_value = sdf_->GetElement ( _tag_name )->Get<T>();
}
ROS_DEBUG ( "%s: <%s> = %s", info(), _tag_name, boost::lexical_cast<std::string> ( _value ).c_str() );
ROS_DEBUG_NAMED("utils", "%s: <%s> = %s", info(), _tag_name, boost::lexical_cast<std::string> ( _value ).c_str() );

}

Expand All @@ -264,7 +264,7 @@ class GazeboRos
void getParameter ( T &_value, const char *_tag_name, const std::map<std::string, T> &_options, const T &_default ) {
_value = _default;
if ( !sdf_->HasElement ( _tag_name ) ) {
ROS_WARN ( "%s: missing <%s> default is %s", info(), _tag_name, boost::lexical_cast<std::string> ( _default ).c_str() );
ROS_WARN_NAMED("utils", "%s: missing <%s> default is %s", info(), _tag_name, boost::lexical_cast<std::string> ( _default ).c_str() );
} else {
this->getParameter<T> ( _value, _tag_name, _options );
}
Expand All @@ -283,18 +283,15 @@ class GazeboRos
std::string value = sdf_->GetElement ( _tag_name )->Get<std::string>();
it = _options.find ( value );
if ( it == _options.end() ) {
ROS_WARN ( "%s: <%s> no matching key to %s", info(), _tag_name, value.c_str() );
ROS_WARN_NAMED("utils", "%s: <%s> no matching key to %s", info(), _tag_name, value.c_str() );
} else {
_value = it->second;
}
}
ROS_DEBUG ( "%s: <%s> = %s := %s", info(), _tag_name, ( it == _options.end() ?"default":it->first.c_str() ), boost::lexical_cast<std::string> ( _value ).c_str() );
ROS_DEBUG_NAMED("utils", "%s: <%s> = %s := %s", info(), _tag_name, ( it == _options.end() ?"default":it->first.c_str() ), boost::lexical_cast<std::string> ( _value ).c_str() );
}
};

typedef boost::shared_ptr<GazeboRos> GazeboRosPtr;
}
#endif



2 changes: 1 addition & 1 deletion gazebo_plugins/src/camera_synchronizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ int main(int argc, char **argv)
VisionReconfigure vr;

double spin_frequency = 100.0;
ROS_INFO("Starting to spin camera_synchronizer at %f Hz...",spin_frequency);
ROS_INFO_NAMED("camera_synchronizer", "Starting to spin camera_synchronizer at %f Hz...",spin_frequency);
vr.spin(spin_frequency);

return 0;
Expand Down
17 changes: 8 additions & 9 deletions gazebo_plugins/src/gazebo_ros_block_laser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,41 +99,41 @@ void GazeboRosBlockLaser::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)

if (!_sdf->HasElement("frameName"))
{
ROS_INFO("Block laser plugin missing <frameName>, defaults to /world");
ROS_INFO_NAMED("block_laser", "Block laser plugin missing <frameName>, defaults to /world");
this->frame_name_ = "/world";
}
else
this->frame_name_ = _sdf->GetElement("frameName")->Get<std::string>();

if (!_sdf->HasElement("topicName"))
{
ROS_INFO("Block laser plugin missing <topicName>, defaults to /world");
ROS_INFO_NAMED("block_laser", "Block laser plugin missing <topicName>, defaults to /world");
this->topic_name_ = "/world";
}
else
this->topic_name_ = _sdf->GetElement("topicName")->Get<std::string>();

if (!_sdf->HasElement("gaussianNoise"))
{
ROS_INFO("Block laser plugin missing <gaussianNoise>, defaults to 0.0");
ROS_INFO_NAMED("block_laser", "Block laser plugin missing <gaussianNoise>, defaults to 0.0");
this->gaussian_noise_ = 0;
}
else
this->gaussian_noise_ = _sdf->GetElement("gaussianNoise")->Get<double>();

if (!_sdf->HasElement("hokuyoMinIntensity"))
{
ROS_INFO("Block laser plugin missing <hokuyoMinIntensity>, defaults to 101");
ROS_INFO_NAMED("block_laser", "Block laser plugin missing <hokuyoMinIntensity>, defaults to 101");
this->hokuyo_min_intensity_ = 101;
}
else
this->hokuyo_min_intensity_ = _sdf->GetElement("hokuyoMinIntensity")->Get<double>();

ROS_INFO("INFO: gazebo_ros_laser plugin should set minimum intensity to %f due to cutoff in hokuyo filters." , this->hokuyo_min_intensity_);
ROS_DEBUG_NAMED("block_laser", "gazebo_ros_laser plugin should set minimum intensity to %f due to cutoff in hokuyo filters." , this->hokuyo_min_intensity_);

if (!_sdf->HasElement("updateRate"))
{
ROS_INFO("Block laser plugin missing <updateRate>, defaults to 0");
ROS_INFO_NAMED("block_laser", "Block laser plugin missing <updateRate>, defaults to 0");
this->update_rate_ = 0;
}
else
Expand All @@ -146,7 +146,7 @@ void GazeboRosBlockLaser::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
// Make sure the ROS node for Gazebo has already been initialized
if (!ros::isInitialized())
{
ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
ROS_FATAL_STREAM_NAMED("block_laser", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
<< "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
return;
}
Expand Down Expand Up @@ -215,7 +215,7 @@ void GazeboRosBlockLaser::OnNewLaserScans()
}
else
{
ROS_INFO("gazebo_ros_block_laser topic name not set");
ROS_INFO_NAMED("block_laser", "gazebo_ros_block_laser topic name not set");
}
}

Expand Down Expand Up @@ -412,4 +412,3 @@ void GazeboRosBlockLaser::OnStats( const boost::shared_ptr<msgs::WorldStatistics


}

8 changes: 4 additions & 4 deletions gazebo_plugins/src/gazebo_ros_bumper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ void GazeboRosBumper::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
this->parentSensor = dynamic_pointer_cast<sensors::ContactSensor>(_parent);
if (!this->parentSensor)
{
ROS_ERROR("Contact sensor parent is not of type ContactSensor");
ROS_ERROR_NAMED("bumper", "Contact sensor parent is not of type ContactSensor");
return;
}

Expand All @@ -90,7 +90,7 @@ void GazeboRosBumper::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
// << this->frame_name_ << std::endl;
if (!_sdf->HasElement("frameName"))
{
ROS_INFO("bumper plugin missing <frameName>, defaults to world");
ROS_INFO_NAMED("bumper", "bumper plugin missing <frameName>, defaults to world");
this->frame_name_ = "world";
}
else
Expand All @@ -99,7 +99,7 @@ void GazeboRosBumper::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
// Make sure the ROS node for Gazebo has already been initialized
if (!ros::isInitialized())
{
ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
ROS_FATAL_STREAM_NAMED("bumper", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
<< "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
return;
}
Expand Down Expand Up @@ -169,7 +169,7 @@ void GazeboRosBumper::OnContact()
// not found
if (!myFrame)
{
ROS_INFO("gazebo_ros_bumper plugin: frameName: %s does not exist"
ROS_INFO_NAMED("bumper", "gazebo_ros_bumper plugin: frameName: %s does not exist"
" yet, will not publish\n",this->frame_name_.c_str());
return;
}
Expand Down
2 changes: 1 addition & 1 deletion gazebo_plugins/src/gazebo_ros_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ void GazeboRosCamera::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
// Make sure the ROS node for Gazebo has already been initialized
if (!ros::isInitialized())
{
ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
ROS_FATAL_STREAM_NAMED("camera", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
<< "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
return;
}
Expand Down
Loading

0 comments on commit 464c8f8

Please sign in to comment.