1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 18:10:47 +02:00

Move debug output to DEBUG stream

This commit is contained in:
Felix Mauch
2019-06-12 09:52:03 +02:00
committed by Tristan Schnell
parent 00d20cb501
commit 75d6ae0a19
5 changed files with 12 additions and 14 deletions

View File

@@ -154,7 +154,7 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h
// Create ros_control interfaces
for (std::size_t i = 0; i < joint_positions_.size(); ++i)
{
ROS_INFO_STREAM("Registing handles for joint " << joint_names_[i]);
ROS_DEBUG_STREAM("Registing handles for joint " << joint_names_[i]);
// Create joint state interface for all joints
js_interface_.registerHandle(hardware_interface::JointStateHandle(joint_names_[i], &joint_positions_[i],
&joint_velocities_[i], &joint_efforts_[i]));
@@ -275,7 +275,6 @@ void HardwareInterface ::write(const ros::Time& time, const ros::Duration& perio
(runtime_state_ == static_cast<uint32_t>(rtde_interface::RUNTIME_STATE::PLAYING) ||
runtime_state_ == static_cast<uint32_t>(rtde_interface::RUNTIME_STATE::PAUSING)))
{
// ROS_INFO_STREAM("Writing command: " << joint_position_command_);
ur_driver_->writeJointCommand(joint_position_command_);
}
}

View File

@@ -69,9 +69,8 @@ int main(int argc, char** argv)
ROS_ERROR_STREAM("Could not correctly initialize robot. Exiting");
exit(1);
}
ROS_INFO_STREAM("initialized hw interface");
ROS_DEBUG_STREAM("initialized hw interface");
controller_manager::ControllerManager cm(g_hw_interface.get(), nh);
ROS_INFO_STREAM("started controller manager");
// Get current time and elapsed time since last read
timestamp = ros::Time::now();
@@ -130,7 +129,6 @@ int main(int argc, char** argv)
double expected_cycle_time = 1.0 / (static_cast<double>(g_hw_interface->getControlFrequency()));
ROS_INFO("Starting control loop");
// Run as fast as possible
while (ros::ok())
{