|
From: <ge...@us...> - 2009-03-20 00:11:42
|
Revision: 12720
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=12720&view=rev
Author: gerkey
Date: 2009-03-20 00:11:39 +0000 (Fri, 20 Mar 2009)
Log Message:
-----------
Lowered verbosity of some common log messages
Modified Paths:
--------------
pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp
pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp
pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp 2009-03-20 00:06:30 UTC (rev 12719)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp 2009-03-20 00:11:39 UTC (rev 12720)
@@ -70,7 +70,7 @@
{
JointPDController * jpc = new JointPDController();
// std::cout<<elt->Attribute("type")<<elt->Attribute("name")<<std::endl;
- ROS_INFO("Joint Position Controller: %s , %s",(elt->Attribute("type")),(elt->Attribute("name")));
+ ROS_DEBUG("Joint Position Controller: %s , %s",(elt->Attribute("type")),(elt->Attribute("name")));
assert(static_cast<std::string>(elt->Attribute("type")) == std::string("JointPDController"));
joint_pd_controllers_.push_back(jpc);
@@ -93,7 +93,7 @@
else
{
trajectory_type_ = std::string(elt->Attribute("interpolation"));
- ROS_INFO("ArmTrajectoryController:: interpolation type:: %s",trajectory_type_.c_str());
+ ROS_DEBUG("ArmTrajectoryController:: interpolation type:: %s",trajectory_type_.c_str());
}
joint_cmd_rt_.resize(joint_pd_controllers_.size());
joint_cmd_dot_rt_.resize(joint_pd_controllers_.size());
@@ -120,7 +120,7 @@
joint_trajectory_->autocalc_timing_ = true;
- ROS_INFO("Size of trajectory points vector : %d",trajectory_points_vector.size());
+ ROS_DEBUG("Size of trajectory points vector : %d",trajectory_points_vector.size());
if(!joint_trajectory_->setTrajectory(trajectory_points_vector))
ROS_WARN("Trajectory not set correctly");
@@ -261,7 +261,7 @@
ArmTrajectoryControllerNode::ArmTrajectoryControllerNode()
: Controller(), node_(ros::Node::instance()), request_trajectory_id_(1), current_trajectory_id_(0), trajectory_wait_timeout_(10.0)
{
- std::cout<<"Controller node created"<<endl;
+ ROS_DEBUG("Controller node created");
c_ = new ArmTrajectoryController();
diagnostics_publisher_ = NULL;
}
@@ -284,7 +284,7 @@
if(topic_name_ptr_ && topic_name_.c_str())
{
- std::cout << "unsub arm controller" << topic_name_ << std::endl;
+ ROS_DEBUG("unsub arm controller %s", topic_name_.c_str());
node_->unsubscribe(topic_name_);
}
delete c_;
@@ -341,17 +341,17 @@
{
ROS_INFO("Loading ArmTrajectoryControllerNode.");
service_prefix_ = config->Attribute("name");
- ROS_INFO("The service_prefix_ is %s",service_prefix_.c_str());
+ ROS_DEBUG("The service_prefix_ is %s",service_prefix_.c_str());
double scale;
node_->param<double>(service_prefix_ + "/velocity_scaling_factor",scale,0.25);
node_->param<double>(service_prefix_ + "/trajectory_wait_timeout",trajectory_wait_timeout_,10.0);
- ROS_INFO("Trajectory wait timeout scale is %f",scale);
+ ROS_DEBUG("Trajectory wait timeout scale is %f",scale);
c_->velocity_scaling_factor_ = std::min(1.0,std::max(0.0,scale));
- ROS_INFO("Velocity scaling factor is %f",c_->velocity_scaling_factor_);
- ROS_INFO("Trajectory wait timeout is %f",trajectory_wait_timeout_);
+ ROS_DEBUG("Velocity scaling factor is %f",c_->velocity_scaling_factor_);
+ ROS_DEBUG("Trajectory wait timeout is %f",trajectory_wait_timeout_);
if(c_->initXml(robot, config)) // Parses subcontroller configuration
{
@@ -371,11 +371,11 @@
topic_name_= topic_name_ptr_->Attribute("name");
if(!topic_name_.c_str())
{
- std::cout<<" A listen _topic is present in the xml file but no name is specified\n";
+ ROS_ERROR(" A listen _topic is present in the xml file but no name is specified");
return false;
}
node_->subscribe(topic_name_, traj_msg_, &ArmTrajectoryControllerNode::CmdTrajectoryReceived, this, 1);
- ROS_INFO("Listening to topic: %s",topic_name_.c_str());
+ ROS_DEBUG("Listening to topic: %s",topic_name_.c_str());
}
getJointTrajectoryThresholds();
@@ -392,14 +392,14 @@
last_diagnostics_publish_time_ = c_->robot_->hw_->current_time_;
node_->param<double>(service_prefix_ + "/diagnostics_publish_delta_time",diagnostics_publish_delta_time_,0.05);
- ROS_INFO("Initialized publisher");
+ ROS_DEBUG("Initialized publisher");
c_->controller_state_publisher_->msg_.name = std::string(service_prefix_);
ROS_INFO("Initialized controller");
return true;
}
- ROS_INFO("Could not initialize controller");
+ ROS_ERROR("Could not initialize controller");
return false;
}
@@ -409,7 +409,7 @@
for(int i=0; i< c_->dimension_;i++)
{
node_->param<double>(service_prefix_ + "/" + c_->joint_pd_controllers_[i]->getJointName() + "/goal_reached_threshold",c_->goal_reached_threshold_[i],GOAL_REACHED_THRESHOLD);
- ROS_INFO("Goal distance threshold for %s is %f",c_->joint_pd_controllers_[i]->getJointName().c_str(),c_->goal_reached_threshold_[i]);
+ ROS_DEBUG("Goal distance threshold for %s is %f",c_->joint_pd_controllers_[i]->getJointName().c_str(),c_->goal_reached_threshold_[i]);
}
}
@@ -467,7 +467,7 @@
void ArmTrajectoryControllerNode::CmdTrajectoryReceived()
{
- ROS_INFO("Trajectory controller:: Cmd received");
+ ROS_DEBUG("Trajectory controller:: Cmd received");
this->ros_lock_.lock();
setTrajectoryCmdFromMsg(traj_msg_);
this->ros_lock_.unlock();
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp 2009-03-20 00:06:30 UTC (rev 12719)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp 2009-03-20 00:11:39 UTC (rev 12720)
@@ -213,7 +213,7 @@
// wait for robotdesc/pr2 on param server
while(!urdf_model_.loadString(xml_content.c_str()))
{
- ROS_INFO("WARNING: base controller is waiting for robotdesc/pr2 in param server. run roslaunch send.xml or similar.");
+ ROS_WARN("base controller is waiting for robotdesc/pr2 in param server. run roslaunch send.xml or similar.");
(ros::g_node)->getParam("robotdesc/pr2",xml_content);
usleep(100000);
}
@@ -322,7 +322,7 @@
bool BaseController::initXml(mechanism::RobotState *robot_state, TiXmlElement *config)
{
- ROS_INFO("BaseController:: name: %s",config->Attribute("name"));
+ ROS_DEBUG("BaseController:: name: %s",config->Attribute("name"));
TiXmlElement *elt = config->FirstChildElement("controller");
std::vector<JointControlParam> jcp_vec;
JointControlParam jcp;
@@ -336,8 +336,8 @@
jcp.joint_name = jnt->Attribute("name");
jcp_vec.push_back(jcp);
- ROS_INFO("BaseController:: joint name: %s",jcp.joint_name.c_str());
- ROS_INFO("BaseController:: controller type: %s\n",jcp.control_type.c_str());
+ ROS_DEBUG("BaseController:: joint name: %s",jcp.joint_name.c_str());
+ ROS_DEBUG("BaseController:: controller type: %s\n",jcp.control_type.c_str());
elt = elt->NextSiblingElement("controller");
}
@@ -372,15 +372,15 @@
max_trans_vel_magnitude_ = fabs(max_vel_.x);
- ROS_INFO("BaseController:: kp_speed %f",kp_speed_);
- ROS_INFO("BaseController:: kp_caster_steer %f",caster_steer_vel_gain_);
- ROS_INFO("BaseController:: timeout %f",timeout_);
- ROS_INFO("BaseController:: max_x_dot %f",(max_vel_.x));
- ROS_INFO("BaseController:: max_y_dot %f",(max_vel_.y));
- ROS_INFO("BaseController:: max_yaw_dot %f",(max_vel_.z));
- ROS_INFO("BaseController:: max_x_accel %f",(max_accel_.x));
- ROS_INFO("BaseController:: max_y_accel %f",(max_accel_.y));
- ROS_INFO("BaseController:: max_yaw_accel %f",(max_accel_.z));
+ ROS_DEBUG("BaseController:: kp_speed %f",kp_speed_);
+ ROS_DEBUG("BaseController:: kp_caster_steer %f",caster_steer_vel_gain_);
+ ROS_DEBUG("BaseController:: timeout %f",timeout_);
+ ROS_DEBUG("BaseController:: max_x_dot %f",(max_vel_.x));
+ ROS_DEBUG("BaseController:: max_y_dot %f",(max_vel_.y));
+ ROS_DEBUG("BaseController:: max_yaw_dot %f",(max_vel_.z));
+ ROS_DEBUG("BaseController:: max_x_accel %f",(max_accel_.x));
+ ROS_DEBUG("BaseController:: max_y_accel %f",(max_accel_.y));
+ ROS_DEBUG("BaseController:: max_yaw_accel %f",(max_accel_.z));
init(jcp_vec,robot_state);
Modified: pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp 2009-03-20 00:06:30 UTC (rev 12719)
+++ pkg/trunk/highlevel/highlevel_controllers/src/move_base.cpp 2009-03-20 00:11:39 UTC (rev 12720)
@@ -579,17 +579,15 @@
}
catch(tf::LookupException& ex)
{
- puts("no odom->base Tx yet");
- ROS_DEBUG("%s\n", ex.what());
+ ROS_DEBUG("No odom->base Tx yet: %s", ex.what());
}
catch(tf::ConnectivityException& ex)
{
- puts("no odom->base Tx yet");
- ROS_DEBUG("%s\n", ex.what());
+ ROS_DEBUG("No odom->base Tx yet: %s\n", ex.what());
}
catch(tf::ExtrapolationException& ex)
{
- puts("Extrapolation exception");
+ ROS_DEBUG("Extrapolation exception");
}
base_odom_.unlock();
Modified: pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp
===================================================================
--- pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp 2009-03-20 00:06:30 UTC (rev 12719)
+++ pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp 2009-03-20 00:11:39 UTC (rev 12720)
@@ -377,7 +377,7 @@
clock_gettime(CLOCK_REALTIME, &init_end);
double duration = 1.0e3 * (init_end.tv_sec - init_start.tv_sec) +
double(init_end.tv_nsec)/1.0e6 - double(init_start.tv_nsec)/1.0e6;
- ROS_INFO(" Initialized %s in %.3lf ms", add_reqs[i].name.c_str(), duration);
+ ROS_DEBUG(" Initialized %s in %.3lf ms", add_reqs[i].name.c_str(), duration);
if (!initialized)
{
delete c;
@@ -419,7 +419,7 @@
double duration = 1.0e3 * (end_time.tv_sec - start_time.tv_sec) +
double(end_time.tv_nsec)/1.0e6 - double(start_time.tv_nsec)/1.0e6;
- ROS_INFO("Controller replacement took %.3lf ms", duration);
+ ROS_DEBUG("Controller replacement took %.3lf ms", duration);
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|