optimize code
This commit is contained in:
@@ -122,6 +122,84 @@ public:
|
||||
static ExecResultCode ParseResultDetail(const std::string & detail);
|
||||
|
||||
private:
|
||||
/**
|
||||
* Initialize core registry objects (action, BT, skill manager).
|
||||
*
|
||||
* Ownership: Creates unique_ptr instances and wires dependencies.
|
||||
* Must be called first in the constructor before any method that relies on
|
||||
* these registries. Safe to call only once (no internal guards).
|
||||
*/
|
||||
void InitializeRegistries();
|
||||
|
||||
/**
|
||||
* Declare ROS 2 parameters used by this node.
|
||||
*
|
||||
* Declaration is separated from parameter retrieval so the logic for
|
||||
* computing defaults (e.g., locating the skills file) happens after all
|
||||
* declarations exist. Idempotent only during construction; not intended for
|
||||
* repeated invocation at runtime.
|
||||
*/
|
||||
void DeclareParameters();
|
||||
|
||||
/**
|
||||
* Resolve the skills definition YAML path.
|
||||
*
|
||||
* If the 'skills_file' parameter is empty, attempts to fall back to the
|
||||
* installed package share directory (brain/config/robot_skills.yaml).
|
||||
*
|
||||
* Returns: Absolute or relative path string (may be empty on failure).
|
||||
*/
|
||||
std::string ResolveSkillsFile();
|
||||
|
||||
/**
|
||||
* Load skill definitions from a YAML file via SkillManager.
|
||||
*
|
||||
* Silently returns if the provided path is empty. Emits a warning log if
|
||||
* parsing/loading fails. Does not throw.
|
||||
*
|
||||
* @param skills_file Path to YAML file (may be empty => no-op).
|
||||
*/
|
||||
void LoadSkills(const std::string & skills_file);
|
||||
|
||||
/**
|
||||
* Retrieve parameter values and apply post-processing.
|
||||
*
|
||||
* Tasks:
|
||||
* - Clamp random_skill_pick_count_ to >= 1.
|
||||
* - Parse allowed_action_skills_ list.
|
||||
* - Parse and store fixed skill sequence.
|
||||
* Logs summary information for visibility. Assumes all parameters already
|
||||
* declared via DeclareParameters().
|
||||
*/
|
||||
void LoadParameters();
|
||||
|
||||
/**
|
||||
* Register per-skill BT node handlers and the unified ExecuteBtAction client.
|
||||
*
|
||||
* This combines two tightly related registration phases to ensure action
|
||||
* client availability for the handlers. Safe to call exactly once during
|
||||
* construction.
|
||||
*/
|
||||
void RegisterBtAndActionClients();
|
||||
|
||||
/**
|
||||
* Create periodic timers:
|
||||
* - bt_timer_: high-frequency BehaviorTree ticking.
|
||||
* - task_timer_: low-frequency sequence/model update trigger.
|
||||
*
|
||||
* Must be invoked after registries & parameters are ready. Not re-entrant.
|
||||
*/
|
||||
void CreateTimers();
|
||||
|
||||
/**
|
||||
* Create external service interfaces (currently a Trigger to force BT rebuild).
|
||||
*
|
||||
* The rebuild service coordinates with atomic flags to avoid unsafe rebuilds
|
||||
* when disallowed. Does not itself perform heavy work; instead triggers the
|
||||
* same path as the periodic task.
|
||||
*/
|
||||
void CreateServices();
|
||||
|
||||
BT::Tree tree_;
|
||||
BT::BehaviorTreeFactory factory_;
|
||||
std::unique_ptr<ActionClientRegistry> action_registry_;
|
||||
|
||||
@@ -33,6 +33,18 @@ namespace brain
|
||||
namespace
|
||||
{
|
||||
|
||||
/**
|
||||
* @brief Determine whether a skill exposes at least one action-capable interface.
|
||||
*
|
||||
* Scans the skill's declared interfaces and treats any entry whose final
|
||||
* component (suffix after the last '.') case-insensitively matches "action" or
|
||||
* "service" as action-capable. Services are included because they can be
|
||||
* wrapped as action-like BT leaves in this framework.
|
||||
*
|
||||
* @param spec SkillSpec to inspect.
|
||||
* @return true if an interface ending with .action or .service is found; false otherwise.
|
||||
* @thread_safety Read-only; safe for concurrent calls.
|
||||
*/
|
||||
bool HasActionInterface(const SkillSpec & spec)
|
||||
{
|
||||
for (const auto & iface : spec.interfaces) {
|
||||
@@ -71,108 +83,17 @@ struct UpdatingFlagGuard
|
||||
CerebrumNode::CerebrumNode(const rclcpp::NodeOptions & options)
|
||||
: rclcpp::Node("cerebrum_node", options)
|
||||
{
|
||||
action_registry_ = std::make_unique<ActionClientRegistry>(this);
|
||||
bt_registry_ = std::make_unique<BTRegistry>(factory_, this);
|
||||
skill_manager_ = std::make_unique<SkillManager>(this, action_registry_.get(), bt_registry_.get());
|
||||
|
||||
// Parameters
|
||||
this->declare_parameter<std::string>("skills_file", "");
|
||||
this->declare_parameter<double>("node_timeout_sec", node_timeout_sec_);
|
||||
this->declare_parameter<bool>(
|
||||
"allow_bt_rebuild_during_execution",
|
||||
allow_bt_rebuild_during_execution_);
|
||||
this->declare_parameter<std::string>("allowed_action_skills", "");
|
||||
this->declare_parameter<std::string>("fixed_skill_sequence", "");
|
||||
this->declare_parameter<int>(
|
||||
"random_skill_pick_count",
|
||||
static_cast<int>(random_skill_pick_count_));
|
||||
|
||||
std::string skills_file;
|
||||
this->get_parameter("skills_file", skills_file);
|
||||
if (skills_file.empty()) {
|
||||
try {
|
||||
auto share = ament_index_cpp::get_package_share_directory("brain");
|
||||
skills_file = share + std::string("/config/robot_skills.yaml");
|
||||
RCLCPP_INFO(this->get_logger(), "Using default skills file: %s", skills_file.c_str());
|
||||
} catch (const std::exception & e) {
|
||||
RCLCPP_WARN(this->get_logger(), "Could not locate default skills file: %s", e.what());
|
||||
}
|
||||
}
|
||||
if (!skills_file.empty()) {
|
||||
if (!skill_manager_->load_from_file(skills_file)) {
|
||||
RCLCPP_WARN(this->get_logger(), "Failed to load skills from %s", skills_file.c_str());
|
||||
}
|
||||
}
|
||||
|
||||
this->get_parameter("node_timeout_sec", node_timeout_sec_);
|
||||
this->get_parameter("allow_bt_rebuild_during_execution", allow_bt_rebuild_during_execution_);
|
||||
int random_pick_param = static_cast<int>(random_skill_pick_count_);
|
||||
this->get_parameter("random_skill_pick_count", random_pick_param);
|
||||
if (random_pick_param < 1) {
|
||||
random_pick_param = 1;
|
||||
}
|
||||
random_skill_pick_count_ = static_cast<std::size_t>(random_pick_param);
|
||||
|
||||
std::string allowed_raw;
|
||||
this->get_parameter("allowed_action_skills", allowed_raw);
|
||||
if (!allowed_raw.empty()) {
|
||||
// parse allowed action skills list
|
||||
allowed_action_skills_ = ParseListString(allowed_raw);
|
||||
RCLCPP_INFO(
|
||||
this->get_logger(),
|
||||
"Allowed action skills count=%zu",
|
||||
allowed_action_skills_.size());
|
||||
}
|
||||
|
||||
std::string fixed_seq_raw;
|
||||
this->get_parameter("fixed_skill_sequence", fixed_seq_raw);
|
||||
if (!fixed_seq_raw.empty()) {
|
||||
auto tmp = ParseListString(fixed_seq_raw);
|
||||
if (!tmp.empty()) {
|
||||
fixed_skill_sequence_ = tmp;
|
||||
}
|
||||
}
|
||||
if (fixed_skill_sequence_) {
|
||||
RCLCPP_INFO(
|
||||
this->get_logger(),
|
||||
"Using fixed skill sequence size=%zu",
|
||||
fixed_skill_sequence_->size());
|
||||
}
|
||||
|
||||
RegisterSkillBtActions();
|
||||
RegisterActionClient();
|
||||
|
||||
bt_timer_ = this->create_wall_timer(
|
||||
10ms,
|
||||
[this]() {
|
||||
ExecuteBehaviorTree();
|
||||
});
|
||||
task_timer_ = this->create_wall_timer(
|
||||
5000ms,
|
||||
[this]() {
|
||||
CerebrumTask();
|
||||
});
|
||||
|
||||
rebuild_service_ = this->create_service<std_srvs::srv::Trigger>(
|
||||
"cerebrum/rebuild_now",
|
||||
[this](
|
||||
const std::shared_ptr<std_srvs::srv::Trigger::Request>,
|
||||
std::shared_ptr<std_srvs::srv::Trigger::Response> resp) {
|
||||
if (bt_pending_run_ && !allow_bt_rebuild_during_execution_) {
|
||||
resp->success = false;
|
||||
resp->message = "BT running and rebuild not allowed";
|
||||
return;
|
||||
}
|
||||
RunVlmModel();
|
||||
CancelActiveExecuteBtGoal();
|
||||
UpdateBehaviorTree();
|
||||
resp->success = true;
|
||||
resp->message = "Rebuild triggered";
|
||||
});
|
||||
|
||||
RCLCPP_INFO(
|
||||
this->get_logger(), "CerebrumNode initialized (timeout=%.2f random_pick=%zu)", node_timeout_sec_,
|
||||
random_skill_pick_count_);
|
||||
InitializeRegistries();
|
||||
DeclareParameters();
|
||||
auto skills_file = ResolveSkillsFile();
|
||||
LoadSkills(skills_file);
|
||||
LoadParameters();
|
||||
RegisterBtAndActionClients();
|
||||
CreateTimers();
|
||||
CreateServices();
|
||||
RCLCPP_INFO(this->get_logger(),
|
||||
"CerebrumNode initialized (timeout=%.2f random_pick=%zu)",
|
||||
node_timeout_sec_, random_skill_pick_count_);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -420,6 +341,20 @@ void CerebrumNode::UpdateBehaviorTree()
|
||||
active_sequence_.c_str());
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Register per-skill BehaviorTree action handlers (leaf nodes).
|
||||
*
|
||||
* For each loaded skill a corresponding BT leaf type <SkillName>_H is
|
||||
* registered (idempotent: duplicate registrations are caught and logged at
|
||||
* debug level). The start handler sends a single-skill ExecuteBtAction goal by
|
||||
* temporarily setting a goal override so that the unified action infrastructure
|
||||
* stays consistent while still yielding per-node granularity. Running and halt
|
||||
* handlers manage timeout enforcement, progress monitoring, and logging.
|
||||
*
|
||||
* Preconditions: skill_manager_ initialized and loaded. Safe to call once
|
||||
* during construction. Subsequent calls will just skip already registered
|
||||
* types.
|
||||
*/
|
||||
void CerebrumNode::RegisterSkillBtActions()
|
||||
{
|
||||
if (!skill_manager_) {return;}
|
||||
@@ -531,6 +466,17 @@ std::vector<std::string> CerebrumNode::PickRandomActionSkills(std::size_t count)
|
||||
return pool;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Convert ordered skill names into a BehaviorTree sequence specification.
|
||||
*
|
||||
* Each skill name is transformed into a BTActionSpec with type and name set to
|
||||
* <Skill>_H (handler leaf). No additional configuration is attached at this
|
||||
* stage; customization would occur earlier at registration time. The function
|
||||
* preserves ordering and reserves storage for efficiency.
|
||||
*
|
||||
* @param names Ordered list of skill identifiers.
|
||||
* @return BTSequenceSpec ready for registration/build.
|
||||
*/
|
||||
BTSequenceSpec CerebrumNode::MakeSequenceFromSkills(const std::vector<std::string> & names)
|
||||
{
|
||||
BTSequenceSpec seq; seq.reserve(names.size());
|
||||
@@ -681,4 +627,173 @@ CerebrumNode::ExecResultCode CerebrumNode::ParseResultDetail(const std::string &
|
||||
return ExecResultCode::UNKNOWN;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initialize registry/manager singletons used by the node.
|
||||
*
|
||||
* Allocates ActionClientRegistry, BTRegistry and SkillManager with proper
|
||||
* dependency ordering so later initialization steps (skill loading, BT
|
||||
* registration) can safely use them. Must be called exactly once during
|
||||
* construction before any other helper depending on these objects.
|
||||
*/
|
||||
void CerebrumNode::InitializeRegistries()
|
||||
{
|
||||
action_registry_ = std::make_unique<ActionClientRegistry>(this);
|
||||
bt_registry_ = std::make_unique<BTRegistry>(factory_, this);
|
||||
skill_manager_ = std::make_unique<SkillManager>(this, action_registry_.get(), bt_registry_.get());
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Declare all ROS 2 parameters consumed by this node.
|
||||
*
|
||||
* Separation of declaration and retrieval enables later logic (like default
|
||||
* skill file resolution) to consult already-declared parameters without
|
||||
* triggering implicit declarations. Not intended for repeated runtime calls.
|
||||
*/
|
||||
void CerebrumNode::DeclareParameters()
|
||||
{
|
||||
this->declare_parameter<std::string>("skills_file", "");
|
||||
this->declare_parameter<double>("node_timeout_sec", node_timeout_sec_);
|
||||
this->declare_parameter<bool>(
|
||||
"allow_bt_rebuild_during_execution",
|
||||
allow_bt_rebuild_during_execution_);
|
||||
this->declare_parameter<std::string>("allowed_action_skills", "");
|
||||
this->declare_parameter<std::string>("fixed_skill_sequence", "");
|
||||
this->declare_parameter<int>(
|
||||
"random_skill_pick_count",
|
||||
static_cast<int>(random_skill_pick_count_));
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Resolve the effective skills definition YAML file path.
|
||||
*
|
||||
* Reads the declared 'skills_file' parameter. If empty, attempts to locate a
|
||||
* packaged default at:
|
||||
* <ament_package_share_directory(brain)>/config/robot_skills.yaml
|
||||
* Fallback discovery failures are logged as warnings; the function never
|
||||
* throws. An empty return value indicates no usable path could be determined.
|
||||
*
|
||||
* @return Resolved skills file path (may be empty if neither parameter nor default exists).
|
||||
* @thread_safety Read-only parameter access; intended for use during construction only.
|
||||
*/
|
||||
std::string CerebrumNode::ResolveSkillsFile()
|
||||
{
|
||||
std::string skills_file;
|
||||
this->get_parameter("skills_file", skills_file);
|
||||
if (skills_file.empty()) {
|
||||
try {
|
||||
auto share = ament_index_cpp::get_package_share_directory("brain");
|
||||
skills_file = share + std::string("/config/robot_skills.yaml");
|
||||
RCLCPP_INFO(this->get_logger(), "Using default skills file: %s", skills_file.c_str());
|
||||
} catch (const std::exception & e) {
|
||||
RCLCPP_WARN(this->get_logger(), "Could not locate default skills file: %s", e.what());
|
||||
}
|
||||
}
|
||||
return skills_file;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Load skill specifications from a YAML file.
|
||||
*
|
||||
* Emits a warning if the file cannot be parsed or loaded, but does not throw.
|
||||
* An empty path results in a no-op so callers can unconditionally invoke it.
|
||||
*
|
||||
* @param skills_file Absolute or relative path to YAML file (may be empty).
|
||||
*/
|
||||
void CerebrumNode::LoadSkills(const std::string & skills_file)
|
||||
{
|
||||
if (skills_file.empty()) {return;}
|
||||
if (!skill_manager_->load_from_file(skills_file)) {
|
||||
RCLCPP_WARN(this->get_logger(), "Failed to load skills from %s", skills_file.c_str());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Retrieve parameter values and apply normalization / parsing.
|
||||
*
|
||||
* Tasks performed:
|
||||
* - Clamp random_skill_pick_count_ to at least 1.
|
||||
* - Parse allowed_action_skills_ delimited list into unique tokens.
|
||||
* - Parse fixed_skill_sequence_ if provided.
|
||||
* - Log summary for transparency.
|
||||
* Safe to call only after DeclareParameters().
|
||||
*/
|
||||
void CerebrumNode::LoadParameters()
|
||||
{
|
||||
this->get_parameter("node_timeout_sec", node_timeout_sec_);
|
||||
this->get_parameter("allow_bt_rebuild_during_execution", allow_bt_rebuild_during_execution_);
|
||||
int random_pick_param = static_cast<int>(random_skill_pick_count_);
|
||||
this->get_parameter("random_skill_pick_count", random_pick_param);
|
||||
if (random_pick_param < 1) {random_pick_param = 1;}
|
||||
random_skill_pick_count_ = static_cast<std::size_t>(random_pick_param);
|
||||
|
||||
std::string allowed_raw;
|
||||
this->get_parameter("allowed_action_skills", allowed_raw);
|
||||
if (!allowed_raw.empty()) {
|
||||
allowed_action_skills_ = ParseListString(allowed_raw);
|
||||
RCLCPP_INFO(this->get_logger(), "Allowed action skills count=%zu", allowed_action_skills_.size());
|
||||
}
|
||||
|
||||
std::string fixed_seq_raw;
|
||||
this->get_parameter("fixed_skill_sequence", fixed_seq_raw);
|
||||
if (!fixed_seq_raw.empty()) {
|
||||
auto tmp = ParseListString(fixed_seq_raw);
|
||||
if (!tmp.empty()) {fixed_skill_sequence_ = tmp;}
|
||||
}
|
||||
if (fixed_skill_sequence_) {
|
||||
RCLCPP_INFO(this->get_logger(), "Using fixed skill sequence size=%zu", fixed_skill_sequence_->size());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Register per-skill BT action handlers plus the unified action client.
|
||||
*
|
||||
* Bundled to ensure the ExecuteBtAction client exists before any BT node can
|
||||
* attempt to send goals. Idempotent in practice because internal registration
|
||||
* functions guard against duplication.
|
||||
*/
|
||||
void CerebrumNode::RegisterBtAndActionClients()
|
||||
{
|
||||
RegisterSkillBtActions();
|
||||
RegisterActionClient();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Create timers used for BT ticking and periodic sequence/model updates.
|
||||
*
|
||||
* bt_timer_: High-frequency (10ms) ticker executing the BT root when a run is pending.
|
||||
* task_timer_: Low-frequency (5s) trigger for model-driven sequence selection and rebuild.
|
||||
*/
|
||||
void CerebrumNode::CreateTimers()
|
||||
{
|
||||
bt_timer_ = this->create_wall_timer(10ms, [this]() {ExecuteBehaviorTree();});
|
||||
task_timer_ = this->create_wall_timer(5000ms, [this]() {CerebrumTask();});
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Create externally callable services.
|
||||
*
|
||||
* Currently exposes a Trigger service to force an immediate sequence rebuild.
|
||||
* The callback enforces rebuild policy (respecting allow_bt_rebuild_during_execution_)
|
||||
* and follows the same steps as the periodic task: model run -> cancel goal -> rebuild.
|
||||
*/
|
||||
void CerebrumNode::CreateServices()
|
||||
{
|
||||
rebuild_service_ = this->create_service<std_srvs::srv::Trigger>(
|
||||
"cerebrum/rebuild_now",
|
||||
[this](
|
||||
const std::shared_ptr<std_srvs::srv::Trigger::Request>,
|
||||
std::shared_ptr<std_srvs::srv::Trigger::Response> resp) {
|
||||
if (bt_pending_run_ && !allow_bt_rebuild_during_execution_) {
|
||||
resp->success = false;
|
||||
resp->message = "BT running and rebuild not allowed";
|
||||
return;
|
||||
}
|
||||
RunVlmModel();
|
||||
CancelActiveExecuteBtGoal();
|
||||
UpdateBehaviorTree();
|
||||
resp->success = true;
|
||||
resp->message = "Rebuild triggered";
|
||||
});
|
||||
}
|
||||
|
||||
} // namespace brain
|
||||
|
||||
@@ -7,6 +7,7 @@
|
||||
#include <rclcpp/rclcpp.hpp>
|
||||
#include <rclcpp_action/rclcpp_action.hpp>
|
||||
#include "brain/cerebellum_node.hpp"
|
||||
#include "brain/constants.hpp"
|
||||
// Legacy MoveToPosition action was removed from automatic server startup.
|
||||
// Adapt test to validate that CerebellumNode brings up the unified ExecuteBtAction server.
|
||||
#include "brain_interfaces/action/execute_bt_action.hpp"
|
||||
@@ -19,7 +20,7 @@ TEST(CerebellumNode, StartsAndProvidesActionServer)
|
||||
auto options = rclcpp::NodeOptions();
|
||||
auto cerebellum = std::make_shared<brain::CerebellumNode>(options);
|
||||
|
||||
auto client = rclcpp_action::create_client<ExecuteBtAction>(cerebellum, "ExecuteBtAction");
|
||||
auto client = rclcpp_action::create_client<ExecuteBtAction>(cerebellum, brain::kExecuteBtActionName);
|
||||
rclcpp::executors::SingleThreadedExecutor exec;
|
||||
exec.add_node(cerebellum);
|
||||
|
||||
|
||||
66
src/brain/test/test_cerebrum_enhanced.cpp
Normal file
66
src/brain/test/test_cerebrum_enhanced.cpp
Normal file
@@ -0,0 +1,66 @@
|
||||
#include <gtest/gtest.h>
|
||||
#include <rclcpp/rclcpp.hpp>
|
||||
#include "brain/cerebrum_node.hpp"
|
||||
|
||||
// NOTE: These tests focus on internal helper behaviors introduced during refactor.
|
||||
// They avoid driving actual action servers; we only validate state transitions
|
||||
// and parameter parsing side-effects.
|
||||
|
||||
using brain::CerebrumNode;
|
||||
|
||||
class CerebrumEnhancedFixture : public ::testing::Test {
|
||||
protected:
|
||||
void SetUp() override {
|
||||
if (!rclcpp::ok()) {int argc = 0; char ** argv = nullptr; rclcpp::init(argc, argv);}
|
||||
node_ = std::make_shared<CerebrumNode>();
|
||||
}
|
||||
void TearDown() override {
|
||||
node_.reset();
|
||||
if (rclcpp::ok()) {rclcpp::shutdown();}
|
||||
}
|
||||
std::shared_ptr<CerebrumNode> node_;
|
||||
};
|
||||
|
||||
TEST_F(CerebrumEnhancedFixture, ResolveSkillsFileAllowsEmptyCustom) {
|
||||
// Recreate node with explicit empty override param to ensure fallback path chosen.
|
||||
rclcpp::NodeOptions opts; opts.append_parameter_override("skills_file", "");
|
||||
auto n2 = std::make_shared<CerebrumNode>(opts);
|
||||
// Can't directly call ResolveSkillsFile (private), but construction log side-effects
|
||||
// are not easily captured; thus we just assert node constructed.
|
||||
SUCCEED();
|
||||
}
|
||||
|
||||
TEST_F(CerebrumEnhancedFixture, RandomSkillPickCountClamp) {
|
||||
rclcpp::NodeOptions opts; opts.append_parameter_override("random_skill_pick_count", 0);
|
||||
auto n2 = std::make_shared<CerebrumNode>(opts);
|
||||
// Indirect validation: pick random should return at least 1 or empty if filtering; just ensure no crash.
|
||||
auto picked = n2->PickRandomActionSkills(5);
|
||||
SUCCEED();
|
||||
}
|
||||
|
||||
TEST_F(CerebrumEnhancedFixture, ParseListStringDeduplicatesOrderPreserved) {
|
||||
auto vec = CerebrumNode::ParseListString("x,x,y,z,y");
|
||||
ASSERT_EQ(vec.size(), 3u);
|
||||
EXPECT_EQ(vec[0], "x");
|
||||
EXPECT_EQ(vec[1], "y");
|
||||
EXPECT_EQ(vec[2], "z");
|
||||
}
|
||||
|
||||
TEST_F(CerebrumEnhancedFixture, RegisterSkillBtActionsIdempotent) {
|
||||
// Call internal registration twice via public sequence selection side-effect.
|
||||
// We can't directly enumerate registrations without accessing BT factory internals.
|
||||
// So we exercise RunVlmModel twice and ensure no crash / exception.
|
||||
node_->RunVlmModel();
|
||||
node_->RunVlmModel();
|
||||
SUCCEED();
|
||||
}
|
||||
|
||||
TEST_F(CerebrumEnhancedFixture, UpdateBehaviorTreeSetsPendingRun) {
|
||||
node_->RunVlmModel();
|
||||
// Force an update cycle
|
||||
node_->CancelActiveExecuteBtGoal();
|
||||
node_->UpdateBehaviorTree();
|
||||
// ExecuteBehaviorTree may clear it quickly; just ensure callable without crash.
|
||||
rclcpp::executors::SingleThreadedExecutor exec; exec.add_node(node_); exec.spin_some();
|
||||
SUCCEED();
|
||||
}
|
||||
@@ -6,6 +6,7 @@
|
||||
#include <rclcpp_action/rclcpp_action.hpp>
|
||||
|
||||
#include "brain/cerebellum_node.hpp"
|
||||
#include "brain/constants.hpp"
|
||||
#include "brain_interfaces/action/execute_bt_action.hpp"
|
||||
#include "interfaces/action/arm_space_control.hpp"
|
||||
|
||||
@@ -72,7 +73,7 @@ TEST(ExecuteBtAction, SingleSkillArmSpaceControlSuccess) {
|
||||
|
||||
// Create ExecuteBtAction client directly (bypassing Cerebrum for unit scope)
|
||||
// Use explicit action name (constant not exported in public headers)
|
||||
auto client = rclcpp_action::create_client<ExecuteBtAction>(cerebellum, "ExecuteBtAction");
|
||||
auto client = rclcpp_action::create_client<ExecuteBtAction>(cerebellum, brain::kExecuteBtActionName);
|
||||
rclcpp::executors::SingleThreadedExecutor exec;
|
||||
exec.add_node(cerebellum);
|
||||
|
||||
|
||||
@@ -3,6 +3,7 @@
|
||||
#include <rclcpp/rclcpp.hpp>
|
||||
#include <rclcpp_action/rclcpp_action.hpp>
|
||||
#include "brain/cerebellum_node.hpp"
|
||||
#include "brain/constants.hpp"
|
||||
#include "brain_interfaces/action/execute_bt_action.hpp"
|
||||
#include "interfaces/action/arm_space_control.hpp"
|
||||
|
||||
@@ -72,7 +73,7 @@ TEST(ExecuteBtActionCancel, CancelMidExecution) {
|
||||
auto node = std::make_shared<brain::CerebellumNode>(opts);
|
||||
auto srv = std::make_shared<SlowArmServer>(node, 2000);
|
||||
rclcpp::executors::SingleThreadedExecutor exec; exec.add_node(node);
|
||||
auto client = rclcpp_action::create_client<ExecuteBtAction>(node, "ExecuteBtAction");
|
||||
auto client = rclcpp_action::create_client<ExecuteBtAction>(node, brain::kExecuteBtActionName);
|
||||
ASSERT_TRUE(
|
||||
spin_until(
|
||||
exec,
|
||||
|
||||
@@ -8,6 +8,7 @@
|
||||
// no stats topic usage here
|
||||
|
||||
#include "brain/cerebellum_node.hpp"
|
||||
#include "brain/constants.hpp"
|
||||
#include "brain_interfaces/action/execute_bt_action.hpp"
|
||||
#include "interfaces/action/arm_space_control.hpp"
|
||||
#include "interfaces/action/hand_control.hpp"
|
||||
@@ -89,7 +90,7 @@ TEST(ExecuteBtActionExtended, MultiSkillProgressSegmentation)
|
||||
auto leg = std::make_shared<SimpleDelayedServer<LegControl>>(node, "LegControl", 180);
|
||||
|
||||
rclcpp::executors::SingleThreadedExecutor exec; exec.add_node(node);
|
||||
auto client = rclcpp_action::create_client<ExecuteBtAction>(node, "ExecuteBtAction");
|
||||
auto client = rclcpp_action::create_client<ExecuteBtAction>(node, brain::kExecuteBtActionName);
|
||||
ASSERT_TRUE(
|
||||
spin_until(
|
||||
exec,
|
||||
|
||||
@@ -3,6 +3,7 @@
|
||||
#include <rclcpp/rclcpp.hpp>
|
||||
#include <rclcpp_action/rclcpp_action.hpp>
|
||||
#include "brain/cerebellum_node.hpp"
|
||||
#include "brain/constants.hpp"
|
||||
#include "brain_interfaces/action/execute_bt_action.hpp"
|
||||
#include "interfaces/action/arm_space_control.hpp"
|
||||
|
||||
@@ -73,7 +74,7 @@ TEST(ExecuteBtActionRunInterp, MultipleRunFeedbacks) {
|
||||
auto node = std::make_shared<brain::CerebellumNode>(opts);
|
||||
auto srv = std::make_shared<DelayedArmServer>(node, 1200);
|
||||
rclcpp::executors::SingleThreadedExecutor exec; exec.add_node(node);
|
||||
auto client = rclcpp_action::create_client<ExecuteBtAction>(node, "ExecuteBtAction");
|
||||
auto client = rclcpp_action::create_client<ExecuteBtAction>(node, brain::kExecuteBtActionName);
|
||||
ASSERT_TRUE(
|
||||
spin_until(
|
||||
exec,
|
||||
|
||||
@@ -4,6 +4,7 @@
|
||||
#include <rclcpp_action/rclcpp_action.hpp>
|
||||
#include <std_msgs/msg/string.hpp>
|
||||
#include "brain/cerebellum_node.hpp"
|
||||
#include "brain/constants.hpp"
|
||||
#include "brain_interfaces/action/execute_bt_action.hpp"
|
||||
#include "interfaces/action/arm_space_control.hpp"
|
||||
|
||||
@@ -68,7 +69,7 @@ TEST(ExecuteBtActionStats, SequenceStatsPublishOrEmptyWhenTimerDisabled) {
|
||||
auto node = std::make_shared<brain::CerebellumNode>(opts);
|
||||
auto server = std::make_shared<ArmFastServer>(node);
|
||||
rclcpp::executors::SingleThreadedExecutor exec; exec.add_node(node);
|
||||
auto client = rclcpp_action::create_client<ExecuteBtAction>(node, "ExecuteBtAction");
|
||||
auto client = rclcpp_action::create_client<ExecuteBtAction>(node, brain::kExecuteBtActionName);
|
||||
ASSERT_TRUE(
|
||||
spin_until(
|
||||
exec,
|
||||
|
||||
@@ -3,6 +3,7 @@
|
||||
#include <rclcpp/rclcpp.hpp>
|
||||
#include <rclcpp_action/rclcpp_action.hpp>
|
||||
#include "brain/cerebellum_node.hpp"
|
||||
#include "brain/constants.hpp"
|
||||
#include "brain_interfaces/action/execute_bt_action.hpp"
|
||||
#include "interfaces/action/arm_space_control.hpp"
|
||||
#include "interfaces/action/hand_control.hpp"
|
||||
@@ -104,7 +105,7 @@ TEST(ExecuteBtActionTimeoutContinue, FirstTimeoutSecondSucceeds) {
|
||||
auto hang = std::make_shared<HangingArmServer>(node);
|
||||
auto hand = std::make_shared<HandQuickServer>(node);
|
||||
rclcpp::executors::SingleThreadedExecutor exec; exec.add_node(node);
|
||||
auto client = rclcpp_action::create_client<ExecuteBtAction>(node, "ExecuteBtAction");
|
||||
auto client = rclcpp_action::create_client<ExecuteBtAction>(node, brain::kExecuteBtActionName);
|
||||
ASSERT_TRUE(
|
||||
spin_until(
|
||||
exec,
|
||||
|
||||
@@ -3,6 +3,7 @@
|
||||
#include <rclcpp/rclcpp.hpp>
|
||||
#include <rclcpp_action/rclcpp_action.hpp>
|
||||
#include "brain/cerebellum_node.hpp"
|
||||
#include "brain/constants.hpp"
|
||||
#include "brain_interfaces/action/execute_bt_action.hpp"
|
||||
#include "interfaces/action/arm_space_control.hpp"
|
||||
|
||||
@@ -71,7 +72,7 @@ TEST(ExecuteBtActionUnsupported, UndefinedFirstSkillAborts) {
|
||||
auto node = std::make_shared<brain::CerebellumNode>(opts);
|
||||
auto arm = std::make_shared<ArmQuickServer>(node);
|
||||
rclcpp::executors::SingleThreadedExecutor exec; exec.add_node(node);
|
||||
auto client = rclcpp_action::create_client<ExecuteBtAction>(node, "ExecuteBtAction");
|
||||
auto client = rclcpp_action::create_client<ExecuteBtAction>(node, brain::kExecuteBtActionName);
|
||||
ASSERT_TRUE(
|
||||
spin_until(
|
||||
exec,
|
||||
|
||||
Reference in New Issue
Block a user