Skip to content

Commit

Permalink
Merge pull request #106 from davetcoleman/kinetic-namespaced
Browse files Browse the repository at this point in the history
Namespaced all ROS_* console output
  • Loading branch information
IanTheEngineer authored Mar 25, 2017
2 parents 220bf86 + b0edf9d commit 1dbee24
Show file tree
Hide file tree
Showing 9 changed files with 57 additions and 57 deletions.
48 changes: 24 additions & 24 deletions baxter_gazebo/src/baxter_gazebo_ros_control_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ class BaxterGazeboRosControlPlugin : public gazebo_ros_control::GazeboRosControl
GazeboRosControlPlugin::Load(parent, sdf);

// Baxter customizations:
ROS_INFO_STREAM_NAMED("baxter_gazebo_ros_control_plugin", "Loading Baxter specific simulation components");
ROS_INFO_STREAM_NAMED("ros_control_plugin", "Loading Baxter specific simulation components");

// Subscribe to a topic that switches' Baxter's msgs
left_command_mode_sub_ = model_nh_.subscribe<baxter_core_msgs::JointCommand>(
Expand Down Expand Up @@ -134,13 +134,13 @@ class BaxterGazeboRosControlPlugin : public gazebo_ros_control::GazeboRosControl
if (!controller_manager_->switchController(start_controllers, stop_controllers,
controller_manager_msgs::SwitchController::Request::BEST_EFFORT))
{
ROS_ERROR_STREAM_NAMED("baxter_gazebo_ros_control_plugin", "Failed to switch controllers");
ROS_ERROR_STREAM_NAMED("ros_control_plugin", "Failed to switch controllers");
}
else
{
// Resetting the command modes to the initial configuration
ROS_INFO("Robot is disabled");
ROS_INFO("Gravity compensation was turned off");
ROS_INFO_NAMED("ros_control_plugin", "Robot is disabled");
ROS_INFO_NAMED("ros_control_plugin", "Gravity compensation was turned off");
right_command_mode_.mode = -1;
left_command_mode_.mode = -1;
head_is_started = false;
Expand All @@ -162,13 +162,13 @@ class BaxterGazeboRosControlPlugin : public gazebo_ros_control::GazeboRosControl
if (!controller_manager_->switchController(start_controllers, stop_controllers,
controller_manager_msgs::SwitchController::Request::STRICT))
{
ROS_ERROR_STREAM_NAMED("baxter_gazebo_ros_control_plugin", "Failed to switch controllers");
ROS_ERROR_STREAM_NAMED("ros_control_plugin", "Failed to switch controllers");
}
else
{
ROS_INFO("Robot is enabled");
ROS_INFO("Left Grippercontroller was successfully started");
ROS_INFO("Gravity compensation was turned on");
ROS_INFO_NAMED("ros_control_plugin", "Robot is enabled");
ROS_INFO_NAMED("ros_control_plugin", "Left Grippercontroller was successfully started");
ROS_INFO_NAMED("ros_control_plugin", "Gravity compensation was turned on");
left_gripper_is_started = true;
is_disabled = false;
}
Expand All @@ -187,13 +187,13 @@ class BaxterGazeboRosControlPlugin : public gazebo_ros_control::GazeboRosControl
if (!controller_manager_->switchController(start_controllers, stop_controllers,
controller_manager_msgs::SwitchController::Request::STRICT))
{
ROS_ERROR_STREAM_NAMED("baxter_gazebo_ros_control_plugin", "Failed to switch controllers");
ROS_ERROR_STREAM_NAMED("ros_control_plugin", "Failed to switch controllers");
}
else
{
ROS_INFO("Robot is enabled");
ROS_INFO("Right Grippercontroller was successfully started");
ROS_INFO("Gravity compensation was turned on");
ROS_INFO_NAMED("ros_control_plugin", "Robot is enabled");
ROS_INFO_NAMED("ros_control_plugin", "Right Grippercontroller was successfully started");
ROS_INFO_NAMED("ros_control_plugin", "Gravity compensation was turned on");
right_gripper_is_started = true;
is_disabled = false;
}
Expand All @@ -212,13 +212,13 @@ class BaxterGazeboRosControlPlugin : public gazebo_ros_control::GazeboRosControl
if (!controller_manager_->switchController(start_controllers, stop_controllers,
controller_manager_msgs::SwitchController::Request::STRICT))
{
ROS_ERROR_STREAM_NAMED("baxter_gazebo_ros_control_plugin", "Failed to switch controllers");
ROS_ERROR_STREAM_NAMED("ros_control_plugin", "Failed to switch controllers");
}
else
{
ROS_INFO("Robot is enabled");
ROS_INFO("Head controller was successfully started");
ROS_INFO("Gravity compensation was turned on");
ROS_INFO_NAMED("ros_control_plugin", "Robot is enabled");
ROS_INFO_NAMED("ros_control_plugin", "Head controller was successfully started");
ROS_INFO_NAMED("ros_control_plugin", "Gravity compensation was turned on");
head_is_started = true;
is_disabled = false;
}
Expand All @@ -240,7 +240,7 @@ class BaxterGazeboRosControlPlugin : public gazebo_ros_control::GazeboRosControl
}
else
{
ROS_WARN_STREAM_NAMED("baxter_gazebo_ros_control_plugin", "Enable the robot");
ROS_WARN_STREAM_NAMED("ros_control_plugin", "Enable the robot");
return;
}
}
Expand All @@ -259,14 +259,14 @@ class BaxterGazeboRosControlPlugin : public gazebo_ros_control::GazeboRosControl
}
else
{
ROS_WARN_STREAM_NAMED("baxter_gazebo_ros_control_plugin", "Enable the robot");
ROS_WARN_STREAM_NAMED("ros_control_plugin", "Enable the robot");
return;
}
}

void modeCommandCallback(const baxter_core_msgs::JointCommandConstPtr& msg, const std::string& side)
{
ROS_DEBUG_STREAM_NAMED("baxter_gazebo_ros_control_plugin", "Switching command mode for side " << side);
ROS_DEBUG_STREAM_NAMED("ros_control_plugin", "Switching command mode for side " << side);

// lock out other thread(s) which are getting called back via ros.
boost::lock_guard<boost::mutex> guard(mtx_);
Expand Down Expand Up @@ -300,7 +300,7 @@ class BaxterGazeboRosControlPlugin : public gazebo_ros_control::GazeboRosControl
stop = side + "_joint_velocity_controller and " + side + "_joint_velocity_controller";
break;
default:
ROS_ERROR_STREAM_NAMED("baxter_gazebo_ros_control_plugin", "Unknown command mode " << msg->mode);
ROS_ERROR_STREAM_NAMED("ros_control_plugin", "Unknown command mode " << msg->mode);
return;
}
// Checks if we have already disabled the controllers
Expand All @@ -317,14 +317,14 @@ class BaxterGazeboRosControlPlugin : public gazebo_ros_control::GazeboRosControl
if (!controller_manager_->switchController(start_controllers, stop_controllers,
controller_manager_msgs::SwitchController::Request::BEST_EFFORT))
{
ROS_ERROR_STREAM_NAMED("baxter_gazebo_ros_control_plugin", "Failed to switch controllers");
ROS_ERROR_STREAM_NAMED("ros_control_plugin", "Failed to switch controllers");
}
else
{
is_disabled = false;
ROS_INFO("Robot is enabled");
ROS_INFO_STREAM(start << " was started and " << stop << " were stopped succesfully");
ROS_INFO("Gravity compensation was turned on");
ROS_INFO_NAMED("ros_control_plugin", "Robot is enabled");
ROS_DEBUG_STREAM_NAMED("ros_control_plugin", "Controller " << start << " started and " << stop << " stopped.");
ROS_INFO_NAMED("ros_control_plugin", "Gravity compensation was turned on by mode command callback");
}
}
};
Expand Down
10 changes: 5 additions & 5 deletions baxter_sim_controllers/src/baxter_effort_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,20 +56,20 @@ bool BaxterEffortController::init(hardware_interface::EffortJointInterface* robo
XmlRpc::XmlRpcValue xml_struct;
if (!nh_.getParam("joints", xml_struct))
{
ROS_ERROR("No 'joints' parameter in controller (namespace '%s')", nh_.getNamespace().c_str());
ROS_ERROR_NAMED("effort", "No 'joints' parameter in controller (namespace '%s')", nh_.getNamespace().c_str());
return false;
}

// Make sure it's a struct
if (xml_struct.getType() != XmlRpc::XmlRpcValue::TypeStruct)
{
ROS_ERROR("The 'joints' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
ROS_ERROR_NAMED("effort", "The 'joints' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
return false;
}

// Get number of joints
n_joints_ = xml_struct.size();
ROS_INFO_STREAM("Initializing BaxterEffortController with " << n_joints_ << " joints.");
ROS_INFO_STREAM_NAMED("effort", "Initializing BaxterEffortController with " << n_joints_ << " joints.");

effort_controllers_.resize(n_joints_);

Expand All @@ -79,7 +79,7 @@ bool BaxterEffortController::init(hardware_interface::EffortJointInterface* robo
// Get joint controller
if (joint_it->second.getType() != XmlRpc::XmlRpcValue::TypeStruct)
{
ROS_ERROR("The 'joints/joint_controller' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
ROS_ERROR_NAMED("effort", "The 'joints/joint_controller' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
return false;
}

Expand All @@ -99,7 +99,7 @@ bool BaxterEffortController::init(hardware_interface::EffortJointInterface* robo

if (!joint_nh.getParam("joint", joint_name[i]))
{
ROS_ERROR("No 'joints' parameter in controller (namespace '%s')", joint_nh.getNamespace().c_str());
ROS_ERROR_NAMED("effort", "No 'joints' parameter in controller (namespace '%s')", joint_nh.getNamespace().c_str());
return false;
}
// Create a publisher for every joint controller that publishes to the command topic under that controller
Expand Down
12 changes: 6 additions & 6 deletions baxter_sim_controllers/src/baxter_gripper_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,20 +51,20 @@ bool BaxterGripperController::init(hardware_interface::EffortJointInterface* rob
XmlRpc::XmlRpcValue xml_struct;
if (!nh_.getParam("joints", xml_struct))
{
ROS_ERROR("No 'joints' parameter in controller (namespace '%s')", nh_.getNamespace().c_str());
ROS_ERROR_NAMED("gripper", "No 'joints' parameter in controller (namespace '%s')", nh_.getNamespace().c_str());
return false;
}

// Make sure it's a struct
if (xml_struct.getType() != XmlRpc::XmlRpcValue::TypeStruct)
{
ROS_ERROR("The 'joints' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
ROS_ERROR_NAMED("gripper", "The 'joints' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
return false;
}

// Get number of joints
n_joints = xml_struct.size();
ROS_INFO_STREAM("Initializing BaxterGripperController with " << n_joints << " joints.");
ROS_INFO_STREAM_NAMED("gripper", "Initializing BaxterGripperController with " << n_joints << " joints.");

gripper_controllers.resize(n_joints);
int i = 0; // track the joint id
Expand All @@ -73,7 +73,7 @@ bool BaxterGripperController::init(hardware_interface::EffortJointInterface* rob
// Get joint controller
if (joint_it->second.getType() != XmlRpc::XmlRpcValue::TypeStruct)
{
ROS_ERROR("The 'joints/joint_controller' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
ROS_ERROR_NAMED("gripper", "The 'joints/joint_controller' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
return false;
}

Expand Down Expand Up @@ -166,7 +166,7 @@ void BaxterGripperController::updateCommands()
// Get latest command
const baxter_core_msgs::EndEffectorCommand& command = *(gripper_command_buffer.readFromRT());

ROS_DEBUG_STREAM("Gripper update commands " << command.command << " " << command.args);
ROS_DEBUG_STREAM_NAMED("gripper", "Gripper update commands " << command.command << " " << command.args);
if (command.command != baxter_core_msgs::EndEffectorCommand::CMD_GO)
return;

Expand All @@ -191,7 +191,7 @@ void BaxterGripperController::updateCommands()
}
#endif
// Update the individual joint controllers
ROS_DEBUG_STREAM(gripper_controllers[main_idx_]->joint_urdf_->name << "->setCommand(" << cmd_position << ")");
ROS_DEBUG_STREAM_NAMED("gripper", gripper_controllers[main_idx_]->joint_urdf_->name << "->setCommand(" << cmd_position << ")");
gripper_controllers[main_idx_]->setCommand(cmd_position);
gripper_controllers[mimic_idx_]->setCommand(gripper_controllers[mimic_idx_]->joint_urdf_->mimic->multiplier *
cmd_position +
Expand Down
8 changes: 4 additions & 4 deletions baxter_sim_controllers/src/baxter_head_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,20 +50,20 @@ bool BaxterHeadController::init(hardware_interface::EffortJointInterface* robot,
XmlRpc::XmlRpcValue xml_struct;
if (!nh_.getParam("joints", xml_struct))
{
ROS_ERROR("No 'joints' parameter in controller (namespace '%s')", nh_.getNamespace().c_str());
ROS_ERROR_NAMED("head", "No 'joints' parameter in controller (namespace '%s')", nh_.getNamespace().c_str());
return false;
}

// Make sure it's a struct
if (xml_struct.getType() != XmlRpc::XmlRpcValue::TypeStruct)
{
ROS_ERROR("The 'joints' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
ROS_ERROR_NAMED("head", "The 'joints' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
return false;
}

// Get number of joints
n_joints = xml_struct.size();
ROS_INFO_STREAM("Initializing BaxterHeadController with " << n_joints << " joints.");
ROS_INFO_STREAM_NAMED("head", "Initializing BaxterHeadController with " << n_joints << " joints.");

head_controllers.resize(n_joints);

Expand All @@ -73,7 +73,7 @@ bool BaxterHeadController::init(hardware_interface::EffortJointInterface* robot,
// Get joint controller
if (joint_it->second.getType() != XmlRpc::XmlRpcValue::TypeStruct)
{
ROS_ERROR("The 'joints/joint_controller' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
ROS_ERROR_NAMED("head", "The 'joints/joint_controller' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
return false;
}

Expand Down
8 changes: 4 additions & 4 deletions baxter_sim_controllers/src/baxter_position_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,20 +61,20 @@ bool BaxterPositionController::init(hardware_interface::EffortJointInterface* ro
XmlRpc::XmlRpcValue xml_struct;
if (!nh_.getParam("joints", xml_struct))
{
ROS_ERROR("No 'joints' parameter in controller (namespace '%s')", nh_.getNamespace().c_str());
ROS_ERROR_NAMED("position", "No 'joints' parameter in controller (namespace '%s')", nh_.getNamespace().c_str());
return false;
}

// Make sure it's a struct
if (xml_struct.getType() != XmlRpc::XmlRpcValue::TypeStruct)
{
ROS_ERROR("The 'joints' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
ROS_ERROR_NAMED("position", "The 'joints' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
return false;
}

// Get number of joints
n_joints_ = xml_struct.size();
ROS_INFO_STREAM("Initializing BaxterPositionController with " << n_joints_ << " joints.");
ROS_INFO_STREAM_NAMED("position", "Initializing BaxterPositionController with " << n_joints_ << " joints.");

position_controllers_.resize(n_joints_);

Expand All @@ -84,7 +84,7 @@ bool BaxterPositionController::init(hardware_interface::EffortJointInterface* ro
// Get joint controller
if (joint_it->second.getType() != XmlRpc::XmlRpcValue::TypeStruct)
{
ROS_ERROR("The 'joints/joint_controller' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
ROS_ERROR_NAMED("position", "The 'joints/joint_controller' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
return false;
}

Expand Down
8 changes: 4 additions & 4 deletions baxter_sim_controllers/src/baxter_velocity_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,20 +61,20 @@ bool BaxterVelocityController::init(hardware_interface::EffortJointInterface* ro
XmlRpc::XmlRpcValue xml_struct;
if (!nh_.getParam("joints", xml_struct))
{
ROS_ERROR("No 'joints' parameter in controller (namespace '%s')", nh_.getNamespace().c_str());
ROS_ERROR_NAMED("velocity", "No 'joints' parameter in controller (namespace '%s')", nh_.getNamespace().c_str());
return false;
}

// Make sure it's a struct
if (xml_struct.getType() != XmlRpc::XmlRpcValue::TypeStruct)
{
ROS_ERROR("The 'joints' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
ROS_ERROR_NAMED("velocity", "The 'joints' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
return false;
}

// Get number of joints
n_joints_ = xml_struct.size();
ROS_INFO_STREAM("Initializing BaxterVelocityController with " << n_joints_ << " joints.");
ROS_INFO_STREAM_NAMED("velocity", "Initializing BaxterVelocityController with " << n_joints_ << " joints.");

velocity_controllers_.resize(n_joints_);

Expand All @@ -84,7 +84,7 @@ bool BaxterVelocityController::init(hardware_interface::EffortJointInterface* ro
// Get joint controller
if (joint_it->second.getType() != XmlRpc::XmlRpcValue::TypeStruct)
{
ROS_ERROR("The 'joints/joint_controller' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
ROS_ERROR_NAMED("velocity", "The 'joints/joint_controller' parameter is not a struct (namespace '%s')", nh_.getNamespace().c_str());
return false;
}

Expand Down
6 changes: 3 additions & 3 deletions baxter_sim_hardware/src/baxter_emulator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -290,9 +290,9 @@ void baxter_emulator::publish(const std::string& img_path)
}
catch (std::exception e)
{
ROS_WARN("Unable to load the Startup picture on Baxter's display screen %s", e.what());
ROS_WARN_NAMED("emulator", "Unable to load the Startup picture on Baxter's display screen %s", e.what());
}
ROS_INFO("Simulator is loaded and started successfully");
ROS_INFO_NAMED("emulator", "Simulator is loaded and started successfully");
std_msgs::Empty started_msg;
sim_started_pub.publish(started_msg);
while (ros::ok())
Expand Down Expand Up @@ -447,7 +447,7 @@ void baxter_emulator::nav_light_cb(const baxter_core_msgs::DigitalOutputCommand&
torso_rightOL_nav_light.state = res;
break;
default:
ROS_ERROR("Not a valid component id");
ROS_ERROR_NAMED("emulator", "Not a valid component id");
break;
}
}
Expand Down
2 changes: 1 addition & 1 deletion baxter_sim_io/src/qnode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -237,7 +237,7 @@ void QNode::run()
ros::spinOnce();
loop_rate.sleep();
}
ROS_INFO("Ros shutdown, proceeding to close the gui.");
ROS_INFO_NAMED("qnode", "Ros shutdown, proceeding to close the gui.");
}

} // namespace baxter_sim_io
Loading

0 comments on commit 1dbee24

Please sign in to comment.