disable some logs
This commit is contained in:
@@ -859,7 +859,7 @@ void CerebellumNode::SetupExecuteBtServer()
|
||||
if (!c.payload_yaml.empty()) {
|
||||
// Log payload content (trim if very long)
|
||||
const std::string payload = c.payload_yaml.size() > 512 ? c.payload_yaml.substr(0, 512) + "..." : c.payload_yaml;
|
||||
RCLCPP_INFO(this->get_logger(), "payload:{%s}", payload.c_str());
|
||||
// RCLCPP_INFO(this->get_logger(), "payload:{%s}", payload.c_str());
|
||||
}
|
||||
}
|
||||
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
|
||||
|
||||
@@ -201,7 +201,7 @@ void CerebrumNode::RegisterActionClient()
|
||||
}
|
||||
robot_work_info_.bt_node_status = "RUNNING";
|
||||
// Debug: log outgoing calls being sent to Cerebellum
|
||||
RCLCPP_INFO(this->get_logger(), "[ExecuteBtAction] Sending goal with calls_count=%zu", g.calls.size());
|
||||
// RCLCPP_INFO(this->get_logger(), "[ExecuteBtAction] Sending goal with calls_count=%zu", g.calls.size());
|
||||
for (size_t i = 0; i < g.calls.size(); ++i) {
|
||||
const auto & c = g.calls[i];
|
||||
RCLCPP_INFO(this->get_logger(), " out_call[%zu]: name=%s interface=%s kind=%s topic=%s payload_len=%zu",
|
||||
@@ -437,7 +437,7 @@ void CerebrumNode::RegisterSkillBtActions()
|
||||
{
|
||||
std::lock_guard<std::mutex> lk(exec_mutex_);
|
||||
if (done_instances_epoch_.find(key) != done_instances_epoch_.end()) {
|
||||
RCLCPP_INFO(this->get_logger(), "[%s/%s] skipped: already SUCCESS in current epoch", bt_type.c_str(), instance_name.c_str());
|
||||
// RCLCPP_INFO(this->get_logger(), "[%s/%s] skipped: already SUCCESS in current epoch", bt_type.c_str(), instance_name.c_str());
|
||||
return BT::NodeStatus::SUCCESS;
|
||||
}
|
||||
}
|
||||
@@ -548,7 +548,7 @@ bool CerebrumNode::UpdateBtActionParamsForSkillInstance(
|
||||
RCLCPP_INFO(this->get_logger(), "Declaring BT action parameters for skill instance %s", instance_name.c_str());
|
||||
try {
|
||||
this->set_parameter(rclcpp::Parameter(p_payload, instance_params));
|
||||
RCLCPP_INFO(this->get_logger(), "Seeded sample payload for %s instance %s", skill_name.c_str(), instance_name.c_str());
|
||||
// RCLCPP_INFO(this->get_logger(), "Seeded sample payload for %s instance %s", skill_name.c_str(), instance_name.c_str());
|
||||
} catch (const std::exception & e) {
|
||||
RCLCPP_ERROR(this->get_logger(), "[%s] seeding sample payload failed: %s", skill_name.c_str(), e.what());
|
||||
return false;
|
||||
@@ -594,8 +594,8 @@ bool CerebrumNode::DeclareBtActionParamsForSkillInstance(
|
||||
return false;
|
||||
} else {
|
||||
instance_params = *params;
|
||||
RCLCPP_INFO(this->get_logger(), "Loaded BT params for %s, instance_params: %s",
|
||||
instance_name.c_str(), instance_params.c_str());
|
||||
// RCLCPP_INFO(this->get_logger(), "Loaded BT params for %s, instance_params: %s",
|
||||
// instance_name.c_str(), instance_params.c_str());
|
||||
}
|
||||
} catch (const std::exception & e) {
|
||||
RCLCPP_ERROR(this->get_logger(), "[%s] read params failed: %s", skill_name.c_str(), e.what());
|
||||
|
||||
Reference in New Issue
Block a user