add payload interfaces between cc

This commit is contained in:
2025-10-19 19:20:51 +08:00
parent 69312b5f81
commit 91a4e32ed9
11 changed files with 566 additions and 19 deletions

View File

@@ -4,6 +4,7 @@
<!-- Retry waist + arm + hand until HandControl_H succeeds -->
<RetryUntilSuccessful name="retry_all_action" num_attempts="5">
<Sequence>
<!-- <MoveHome_H name="s0_move_home" /> -->
<MoveWaist_H name="s1_waist_bend_down" /> <!--pitch w rad -->
<Arm_H name="s2_arm_stretch_out" />
<HandControl_H name="s3_hand_pickup" />
@@ -12,13 +13,13 @@
<MoveWaist_H name="s6_waist_turn_around" />
<MoveLeg_H name="s7_leg_move_back" />
<MoveWheel_H name="s8_wheel_move_back" />
<MoveWaist_H name="s8_waist_bend_down" />
<Arm_H name="s9_arm_stretch_out" />
<HandControl_H name="s10_hand_release" />
<Arm_H name="s11_arm_move_to_snapshot_pose" />
<CameraTakePhoto_H name="s12_camera_take_photo" />
<MoveWaist_H name="s13_waist_bend_up" />
<Arm_H name="s14_arm_retract" />
<MoveWaist_H name="s9_waist_bend_down" />
<Arm_H name="s10_arm_stretch_out" />
<HandControl_H name="s11_hand_release" />
<Arm_H name="s12_arm_move_to_snapshot_pose" />
<CameraTakePhoto_H name="s13_camera_take_photo" />
<MoveWaist_H name="s14_waist_bend_up" />
<Arm_H name="s15_arm_retract" />
</Sequence>
</RetryUntilSuccessful>
</Sequence>

View File

@@ -4,6 +4,18 @@
interfaces:
- VisionObjectRecognition.srv
- name: MapLoad
version: 1.0.0
description: "加载地图"
interfaces:
- MapLoad.srv
- name: MapSave
version: 1.0.0
description: "保存地图"
interfaces:
- MapSave.srv
- name: Arm
version: 1.0.0
description: "手臂控制"

View File

@@ -10,11 +10,15 @@
#include <std_msgs/msg/string.hpp>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
#include <yaml-cpp/yaml.h>
#include "brain_interfaces/action/execute_bt_action.hpp"
#include "brain_interfaces/msg/skill_call.hpp"
#include "brain/action_registry.hpp"
#include "brain/skill_manager.hpp"
#include <smacc2/smacc_signal_detector.hpp>
#include "brain/sm_cerebellum.hpp" // for CerebellumData::ExecResult
// For from_yaml<T>(YAML::Node)
#include "brain/payload_converters.hpp"
namespace brain
{
@@ -81,15 +85,53 @@ private:
// Current accepted sequence epoch (from client) used to filter/reject stale goals
std::atomic<uint32_t> current_epoch_{0};
// Latest ExecuteBtAction calls (Plan A minimal support); guarded by implicit action server thread confinement
std::vector<brain_interfaces::msg::SkillCall> last_calls_;
// Lookup the SkillCall for a given skill name in the latest goal, if any
const brain_interfaces::msg::SkillCall * FindCallForSkill(const std::string & name) const
{
for (const auto & c : last_calls_) {
if (c.name == name) return &c;
}
return nullptr;
}
std::atomic<double> nav2_last_distance_remaining_{std::numeric_limits<double>::quiet_NaN()};
std::atomic<bool> nav2_last_goal_succeeded_{false};
// ---- helpers ----
/**
* @brief Try to parse the current goal's per-call YAML payload into a typed object.
*
* Looks up the latest ExecuteBtAction.goal.calls entry matching skill_name, and if
* payload_yaml is non-empty attempts to YAML::Load and convert via brain::from_yaml<T>.
* On success, writes into 'out' and returns true; on failure returns false and leaves 'out' unchanged.
*/
template<typename T>
bool TryParseCallPayload(const std::string & skill_name, T & out) const
{
if (last_calls_.empty()) {return false;}
for (const auto & c : last_calls_) {
if (c.name == skill_name && !c.payload_yaml.empty()) {
try {
auto node = YAML::Load(c.payload_yaml);
out = brain::from_yaml<T>(node);
return true;
} catch (const std::exception & e) {
RCLCPP_WARN(rclcpp::Node::get_logger(), "[%s] payload_yaml parse failed: %s",
skill_name.c_str(), e.what());
}
break;
}
}
return false;
}
/** @brief Install application-specific action hook overrides for skill manager. */
void ConfigureActionHooks();
void ConfigureArmSpaceControlHooks();
void ConfigureArmHooks();
void ConfigureHandControlHooks();
void ConfigureCameraTakePhotoHooks();
void ConfigureLegControlHooks();
void ConfigureVisionGraspObjectHooks();
void ConfigureSlamModeHooks();
@@ -102,6 +144,8 @@ private:
/** @brief Install application-specific service hook overrides. */
void ConfigureServiceHooks();
void ConfigureVisionObjectRecognitionHooks();
void ConfigureMapLoadHooks();
void ConfigureMapSaveHooks();
/**
* @brief Parse a raw comma / semicolon / whitespace separated list of skill names.

View File

@@ -18,6 +18,8 @@
#include "brain/constants.hpp"
#include "brain/epoch_filter.hpp"
#include <std_srvs/srv/trigger.hpp>
// For ExecuteBtAction SkillCall building
#include "brain_interfaces/msg/skill_call.hpp"
namespace brain
@@ -201,6 +203,12 @@ private:
*/
void CreateServices();
// ---- Per-BT-action dynamic parameter support ----
/** Declare per-skill parameter entries used to customize outgoing calls. */
void DeclareBtActionParamsForSkill(const std::string & skill_name);
/** Build a SkillCall message for given skill by consulting SkillSpec and per-skill params. */
brain_interfaces::msg::SkillCall BuildSkillCallForSkill(const std::string & skill_name) const;
BT::Tree tree_;
BT::BehaviorTreeFactory factory_;
std::unique_ptr<ActionClientRegistry> action_registry_;

View File

@@ -0,0 +1,228 @@
#pragma once
#include <yaml-cpp/yaml.h>
#include <string>
#include "interfaces/action/move_waist.hpp"
#include "interfaces/action/move_leg.hpp"
#include "interfaces/action/move_wheel.hpp"
#include "interfaces/action/hand_control.hpp"
#include "interfaces/action/arm.hpp"
#include "interfaces/action/slam_mode.hpp"
#include "interfaces/action/camera_take_photo.hpp"
#include "interfaces/action/arm_space_control.hpp"
#include "interfaces/action/leg_control.hpp"
#include "interfaces/action/move_home.hpp"
#include "interfaces/action/move_to_position.hpp"
#include "interfaces/action/vision_grasp_object.hpp"
#include "interfaces/srv/vision_object_recognition.hpp"
#include "interfaces/srv/map_load.hpp"
#include "interfaces/srv/map_save.hpp"
namespace brain {
template<typename T>
T from_yaml(const YAML::Node & n);
// MoveWaist::Goal: move_pitch_degree, move_yaw_degree
template<>
inline interfaces::action::MoveWaist::Goal from_yaml<interfaces::action::MoveWaist::Goal>(const YAML::Node & n)
{
interfaces::action::MoveWaist::Goal g;
if (n && n.IsMap()) {
if (n["move_pitch_degree"]) g.move_pitch_degree = n["move_pitch_degree"].as<float>();
if (n["move_yaw_degree"]) g.move_yaw_degree = n["move_yaw_degree"].as<float>();
}
return g;
}
// MoveLeg::Goal: move_up_distance
template<>
inline interfaces::action::MoveLeg::Goal from_yaml<interfaces::action::MoveLeg::Goal>(const YAML::Node & n)
{
interfaces::action::MoveLeg::Goal g;
if (n && n.IsMap()) {
if (n["move_up_distance"]) g.move_up_distance = n["move_up_distance"].as<float>();
}
return g;
}
// MoveWheel::Goal: move_distance, move_angle
template<>
inline interfaces::action::MoveWheel::Goal from_yaml<interfaces::action::MoveWheel::Goal>(const YAML::Node & n)
{
interfaces::action::MoveWheel::Goal g;
if (n && n.IsMap()) {
if (n["move_distance"]) g.move_distance = n["move_distance"].as<float>();
if (n["move_angle"]) g.move_angle = n["move_angle"].as<float>();
}
return g;
}
// HandControl::Goal: mode
template<>
inline interfaces::action::HandControl::Goal from_yaml<interfaces::action::HandControl::Goal>(const YAML::Node & n)
{
interfaces::action::HandControl::Goal g;
if (n && n.IsMap()) {
if (n["mode"]) g.mode = n["mode"].as<int32_t>();
}
return g;
}
// Arm::Goal: body_id, data_type, command_id, data_array, frame_time_stamp, data_length
template<>
inline interfaces::action::Arm::Goal from_yaml<interfaces::action::Arm::Goal>(const YAML::Node & n)
{
interfaces::action::Arm::Goal g;
if (n && n.IsMap()) {
if (n["body_id"]) g.body_id = n["body_id"].as<int32_t>();
if (n["data_type"]) g.data_type = n["data_type"].as<int32_t>();
if (n["command_id"]) g.command_id = n["command_id"].as<int64_t>();
if (n["frame_time_stamp"]) g.frame_time_stamp = n["frame_time_stamp"].as<int64_t>();
if (n["data_array"]) {
auto vec = n["data_array"].as<std::vector<double>>();
g.data_array.assign(vec.begin(), vec.end());
g.data_length = static_cast<int32_t>(g.data_array.size());
}
if (n["data_length"]) g.data_length = n["data_length"].as<int32_t>();
}
return g;
}
// SlamMode::Goal: enable_mapping
template<>
inline interfaces::action::SlamMode::Goal from_yaml<interfaces::action::SlamMode::Goal>(const YAML::Node & n)
{
interfaces::action::SlamMode::Goal g;
if (n && n.IsMap()) {
if (n["enable_mapping"]) g.enable_mapping = n["enable_mapping"].as<bool>();
}
return g;
}
// CameraTakePhoto::Goal: mode, effort
template<>
inline interfaces::action::CameraTakePhoto::Goal from_yaml<interfaces::action::CameraTakePhoto::Goal>(const YAML::Node & n)
{
interfaces::action::CameraTakePhoto::Goal g;
if (n && n.IsMap()) {
if (n["mode"]) g.mode = n["mode"].as<int32_t>();
if (n["effort"]) g.effort = n["effort"].as<float>();
}
return g;
}
// ArmSpaceControl::Goal: target (geometry_msgs::msg::PoseStamped)
template<>
inline interfaces::action::ArmSpaceControl::Goal from_yaml<interfaces::action::ArmSpaceControl::Goal>(const YAML::Node & n)
{
interfaces::action::ArmSpaceControl::Goal g;
// Only support position/orientation fields in a simple map if provided
if (n && n.IsMap()) {
auto & pose = g.target;
if (n["frame_id"]) pose.header.frame_id = n["frame_id"].as<std::string>();
if (n["stamp_sec"]) pose.header.stamp.sec = n["stamp_sec"].as<int32_t>();
if (n["stamp_nanosec"]) pose.header.stamp.nanosec = n["stamp_nanosec"].as<uint32_t>();
if (auto p = n["position"]) {
if (p["x"]) pose.pose.position.x = p["x"].as<double>();
if (p["y"]) pose.pose.position.y = p["y"].as<double>();
if (p["z"]) pose.pose.position.z = p["z"].as<double>();
}
if (auto q = n["orientation"]) {
if (q["x"]) pose.pose.orientation.x = q["x"].as<double>();
if (q["y"]) pose.pose.orientation.y = q["y"].as<double>();
if (q["z"]) pose.pose.orientation.z = q["z"].as<double>();
if (q["w"]) pose.pose.orientation.w = q["w"].as<double>();
}
}
return g;
}
// LegControl::Goal: target (geometry_msgs::msg::TwistStamped)
template<>
inline interfaces::action::LegControl::Goal from_yaml<interfaces::action::LegControl::Goal>(const YAML::Node & n)
{
interfaces::action::LegControl::Goal g;
if (n && n.IsMap()) {
auto & t = g.target;
if (n["frame_id"]) t.header.frame_id = n["frame_id"].as<std::string>();
if (n["stamp_sec"]) t.header.stamp.sec = n["stamp_sec"].as<int32_t>();
if (n["stamp_nanosec"]) t.header.stamp.nanosec = n["stamp_nanosec"].as<uint32_t>();
if (auto lin = n["linear"]) {
if (lin["x"]) t.twist.linear.x = lin["x"].as<double>();
if (lin["y"]) t.twist.linear.y = lin["y"].as<double>();
if (lin["z"]) t.twist.linear.z = lin["z"].as<double>();
}
if (auto ang = n["angular"]) {
if (ang["x"]) t.twist.angular.x = ang["x"].as<double>();
if (ang["y"]) t.twist.angular.y = ang["y"].as<double>();
if (ang["z"]) t.twist.angular.z = ang["z"].as<double>();
}
}
return g;
}
// MoveHome::Goal: empty; accept any map and ignore
template<>
inline interfaces::action::MoveHome::Goal from_yaml<interfaces::action::MoveHome::Goal>(const YAML::Node & n)
{
(void)n; return interfaces::action::MoveHome::Goal{};
}
// MoveToPosition::Goal: target_x, target_y
template<>
inline interfaces::action::MoveToPosition::Goal from_yaml<interfaces::action::MoveToPosition::Goal>(const YAML::Node & n)
{
interfaces::action::MoveToPosition::Goal g;
if (n && n.IsMap()) {
if (n["target_x"]) g.target_x = n["target_x"].as<float>();
if (n["target_y"]) g.target_y = n["target_y"].as<float>();
}
return g;
}
// VisionGraspObject::Goal: object_id
template<>
inline interfaces::action::VisionGraspObject::Goal from_yaml<interfaces::action::VisionGraspObject::Goal>(const YAML::Node & n)
{
interfaces::action::VisionGraspObject::Goal g;
if (n && n.IsMap()) {
if (n["object_id"]) g.object_id = n["object_id"].as<std::string>();
}
return g;
}
// MapLoad::Request: map_url
template<>
inline interfaces::srv::MapLoad::Request from_yaml<interfaces::srv::MapLoad::Request>(const YAML::Node & n)
{
interfaces::srv::MapLoad::Request r;
if (n && n.IsMap()) {
if (n["map_url"]) r.map_url = n["map_url"].as<std::string>();
}
return r;
}
// MapSave::Request: map_url
template<>
inline interfaces::srv::MapSave::Request from_yaml<interfaces::srv::MapSave::Request>(const YAML::Node & n)
{
interfaces::srv::MapSave::Request r;
if (n && n.IsMap()) {
if (n["map_url"]) r.map_url = n["map_url"].as<std::string>();
}
return r;
}
// VisionObjectRecognition::Request: camera_position
template<>
inline interfaces::srv::VisionObjectRecognition::Request from_yaml<interfaces::srv::VisionObjectRecognition::Request>(const YAML::Node & n)
{
interfaces::srv::VisionObjectRecognition::Request r;
if (n && n.IsMap()) {
if (n["camera_position"]) r.camera_position = n["camera_position"].as<std::string>();
}
return r;
}
} // namespace brain

View File

@@ -11,6 +11,8 @@
#include "interfaces/action/move_leg.hpp"
#include "interfaces/action/move_waist.hpp"
#include "interfaces/action/move_wheel.hpp"
#include "interfaces/srv/map_load.hpp"
#include "interfaces/srv/map_save.hpp"
#include "interfaces/srv/vision_object_recognition.hpp"
namespace brain {
@@ -32,7 +34,9 @@ using SkillActionTypes = std::tuple<
>;
using SkillServiceTypes = std::tuple<
interfaces::srv::VisionObjectRecognition
interfaces::srv::VisionObjectRecognition,
interfaces::srv::MapLoad,
interfaces::srv::MapSave
>;
template<>
@@ -105,4 +109,18 @@ struct SkillServiceTrait<interfaces::srv::VisionObjectRecognition>
static constexpr const char * default_topic = "";
};
template<>
struct SkillServiceTrait<interfaces::srv::MapLoad>
{
static constexpr const char * skill_name = "MapLoad";
static constexpr const char * default_topic = "";
};
template<>
struct SkillServiceTrait<interfaces::srv::MapSave>
{
static constexpr const char * skill_name = "MapSave";
static constexpr const char * default_topic = "";
};
} // namespace brain

View File

@@ -38,6 +38,7 @@
#include "interfaces/action/arm.hpp"
#include "interfaces/action/vision_grasp_object.hpp"
#include "brain_interfaces/action/execute_bt_action.hpp" // ExecuteBtAction bridge
#include "brain/payload_converters.hpp"
#include "interfaces/action/slam_mode.hpp"
#include "interfaces/srv/vision_object_recognition.hpp"
#include "interfaces/srv/map_save.hpp"
@@ -102,7 +103,8 @@ void CerebellumNode::ConfigureArmHooks()
SkillManager::ActionHookOptions<interfaces::action::Arm> hooks;
hooks.make_goal = [this](const std::string & skill_name) {
interfaces::action::Arm::Goal goal{};
// Plan A: per-call YAML overrides
(void)TryParseCallPayload<interfaces::action::Arm::Goal>(skill_name, goal);
goal.body_id = (tls_arm_body_id == 0 || tls_arm_body_id == 1) ? tls_arm_body_id : 0; // LEFT_ARM=0, RIGHT_ARM=1
goal.data_type = 3; //ARM_COMMAND_TYPE_POSE_DIRECT_MOVE
goal.command_id = ++command_id_;
@@ -207,6 +209,8 @@ void CerebellumNode::ConfigureHandControlHooks()
SkillManager::ActionHookOptions<interfaces::action::HandControl> hooks;
hooks.make_goal = [this](const std::string & skill_name) {
interfaces::action::HandControl::Goal goal{};
// Plan A: per-call YAML overrides
(void)TryParseCallPayload<interfaces::action::HandControl::Goal>(skill_name, goal);
const std::string param = "hand_control.target_pose";
if (!this->has_parameter(param)) {
this->declare_parameter<std::vector<double>>(param, {0.0, 0.0, 0.0});
@@ -262,8 +266,11 @@ void CerebellumNode::ConfigureMoveWaistHooks()
SkillManager::ActionHookOptions<interfaces::action::MoveWaist> hooks;
hooks.make_goal = [this](const std::string & skill_name) {
interfaces::action::MoveWaist::Goal goal{};
//TODO
// Plan A: load per-call YAML payload into goal if present
(void)TryParseCallPayload<interfaces::action::MoveWaist::Goal>(skill_name, goal);
RCLCPP_INFO(this->get_logger(), "[%s] move_pitch_degree: %f, move_yaw_degree: %f", skill_name.c_str(), goal.move_pitch_degree, goal.move_yaw_degree);
return goal;
};
hooks.on_feedback = [this](
@@ -310,8 +317,7 @@ void CerebellumNode::ConfigureMoveLegHooks()
SkillManager::ActionHookOptions<interfaces::action::MoveLeg> hooks;
hooks.make_goal = [this](const std::string & skill_name) {
interfaces::action::MoveLeg::Goal goal{};
//TODO
(void)TryParseCallPayload<interfaces::action::MoveLeg::Goal>(skill_name, goal);
return goal;
};
hooks.on_feedback = [this](
@@ -358,7 +364,8 @@ void CerebellumNode::ConfigureMoveWheelHooks()
SkillManager::ActionHookOptions<interfaces::action::MoveWheel> hooks;
hooks.make_goal = [this](const std::string & skill_name) {
interfaces::action::MoveWheel::Goal goal{};
//TODO
// Plan A: per-call YAML overrides
(void)TryParseCallPayload<interfaces::action::MoveWheel::Goal>(skill_name, goal);
return goal;
};
@@ -406,7 +413,8 @@ void CerebellumNode::ConfigureMoveHomeHooks()
SkillManager::ActionHookOptions<interfaces::action::MoveHome> hooks;
hooks.make_goal = [this](const std::string & skill_name) {
interfaces::action::MoveHome::Goal goal{};
//TODO
// Plan A: per-call YAML overrides (even though goal is empty)
(void)TryParseCallPayload<interfaces::action::MoveHome::Goal>(skill_name, goal);
return goal;
};
@@ -456,6 +464,7 @@ void CerebellumNode::ConfigureActionHooks()
}
ConfigureArmHooks();
ConfigureHandControlHooks();
ConfigureCameraTakePhotoHooks();
ConfigureMoveWaistHooks();
ConfigureMoveLegHooks();
ConfigureMoveWheelHooks();
@@ -478,8 +487,12 @@ void CerebellumNode::ConfigureVisionObjectRecognitionHooks()
return std::chrono::seconds(5);
};
hooks.make_request = [this](const std::string & skill_name) {
(void)skill_name;
auto req = std::make_shared<VisionSrv::Request>();
auto req = std::make_shared<VisionSrv::Request>();
// Prefer payload_yaml from calls
if (TryParseCallPayload<VisionSrv::Request>(skill_name, *req)) {
return req;
}
// fallback to parameter
const std::string param = "vision_object_recognition.camera_position";
if (!this->has_parameter(param)) {
this->declare_parameter<std::string>(param, std::string("left"));
@@ -537,6 +550,107 @@ void CerebellumNode::ConfigureVisionObjectRecognitionHooks()
}
}
void CerebellumNode::ConfigureCameraTakePhotoHooks()
{
// CameraTakePhoto
SkillManager::ActionHookOptions<interfaces::action::CameraTakePhoto> hooks;
hooks.make_goal = [this](const std::string & skill_name) {
interfaces::action::CameraTakePhoto::Goal goal{};
(void)TryParseCallPayload<interfaces::action::CameraTakePhoto::Goal>(skill_name, goal);
return goal;
};
hooks.on_result = [this](
const std::string & skill_name,
const ActionClientRegistry::GoalHandle<interfaces::action::CameraTakePhoto>::WrappedResult & res) {
const bool success = res.code == rclcpp_action::ResultCode::SUCCEEDED && res.result && res.result->success;
const std::string message = res.result ? res.result->message : std::string("无返回信息");
if (success) {
RCLCPP_INFO(this->get_logger(), "[%s] 成功: %s", skill_name.c_str(), message.c_str());
} else if (res.code == rclcpp_action::ResultCode::CANCELED) {
RCLCPP_WARN(this->get_logger(), "[%s] 被取消", skill_name.c_str());
} else {
RCLCPP_ERROR(this->get_logger(), "[%s] 失败 (code=%d): %s",
skill_name.c_str(), static_cast<int>(res.code), message.c_str());
}
};
hooks.on_goal_response = [this](
const std::string & skill_name,
const std::shared_ptr<ActionClientRegistry::GoalHandle<interfaces::action::CameraTakePhoto>> & handle) {
if (static_cast<bool>(handle)) {
RCLCPP_INFO(this->get_logger(), "[%s] goal 已被服务器接收", skill_name.c_str());
} else {
RCLCPP_WARN(this->get_logger(), "[%s] goal 被服务器拒绝", skill_name.c_str());
}
};
skill_manager_->configure_action_hooks<interfaces::action::CameraTakePhoto>("CameraTakePhoto", std::move(hooks));
}
void CerebellumNode::ConfigureMapLoadHooks()
{
using MapLoadSrv = interfaces::srv::MapLoad;
SkillManager::ServiceHookOptions<MapLoadSrv> hooks;
hooks.wait_timeout = [](const std::string &) { return std::chrono::seconds(2); };
hooks.call_timeout = [](const std::string &) { return std::chrono::seconds(5); };
hooks.make_request = [this](const std::string & skill_name) {
auto req = std::make_shared<MapLoadSrv::Request>();
if (TryParseCallPayload<MapLoadSrv::Request>(skill_name, *req)) { return req; }
// Fallback to parameter
if (!this->has_parameter("map_load_url")) {
this->declare_parameter<std::string>("map_load_url", std::string(""));
}
req->map_url = this->get_parameter("map_load_url").as_string();
return req;
};
hooks.on_response = [this](
const std::string & skill_name,
const SkillManager::ServiceHookOptions<MapLoadSrv>::ClientPtr &,
const SkillManager::ServiceHookOptions<MapLoadSrv>::ResponsePtr & resp,
std::string & detail) {
// MapLoad response schema may not include a message field; rely on success only
detail = resp->success ? std::string("ok") : std::string("failed");
if (!resp->success) {
RCLCPP_WARN(this->get_logger(), "[%s] MapLoad failed: %s", skill_name.c_str(), detail.c_str());
} else {
RCLCPP_INFO(this->get_logger(), "[%s] MapLoad: %s", skill_name.c_str(), detail.c_str());
}
return resp->success;
};
skill_manager_->configure_service_hooks<MapLoadSrv>("MapLoad", std::move(hooks));
}
void CerebellumNode::ConfigureMapSaveHooks()
{
using MapSaveSrv = interfaces::srv::MapSave;
SkillManager::ServiceHookOptions<MapSaveSrv> hooks;
hooks.wait_timeout = [](const std::string &) { return std::chrono::seconds(2); };
hooks.call_timeout = [](const std::string &) { return std::chrono::seconds(5); };
hooks.make_request = [this](const std::string & skill_name) {
auto req = std::make_shared<MapSaveSrv::Request>();
if (TryParseCallPayload<MapSaveSrv::Request>(skill_name, *req)) { return req; }
// Fallback to parameter group
if (!this->has_parameter("map_save_url")) {
this->declare_parameter<std::string>("map_save_url", std::string("/tmp/humanoid_map"));
}
req->map_url = this->get_parameter("map_save_url").as_string();
return req;
};
hooks.on_response = [this](
const std::string & skill_name,
const SkillManager::ServiceHookOptions<MapSaveSrv>::ClientPtr &,
const SkillManager::ServiceHookOptions<MapSaveSrv>::ResponsePtr & resp,
std::string & detail) {
// MapSave response schema may not include a message field; rely on success only
detail = resp->success ? std::string("ok") : std::string("failed");
if (!resp->success) {
RCLCPP_WARN(this->get_logger(), "[%s] MapSave failed: %s", skill_name.c_str(), detail.c_str());
} else {
RCLCPP_INFO(this->get_logger(), "[%s] MapSave: %s", skill_name.c_str(), detail.c_str());
}
return resp->success;
};
skill_manager_->configure_service_hooks<MapSaveSrv>("MapSave", std::move(hooks));
}
/**
* @brief Configure Service hooks for various movements.
*
@@ -548,6 +662,8 @@ void CerebellumNode::ConfigureServiceHooks()
return;
}
ConfigureVisionObjectRecognitionHooks();
ConfigureMapLoadHooks();
ConfigureMapSaveHooks();
}
/**
@@ -928,6 +1044,9 @@ std::string CerebellumNode::GetInterfaceKind(const SkillSpec & spec) const
for (auto & c : kind) {
c = static_cast<char>(::tolower(static_cast<unsigned char>(c)));
}
// Normalize common variants
if (kind == "service") return "service";
if (kind == "srv") return "service";
return kind;
}
@@ -1220,6 +1339,9 @@ void CerebellumNode::RunExecuteBtGoal(
if (!ValidateAndParseGoal(goal_handle, skills)) {
return; // goal aborted
}
// Cache calls for this goal (Plan A minimal support)
last_calls_.clear();
for (const auto & c : goal_handle->get_goal()->calls) { last_calls_.push_back(c); }
// Install execute_fn & complete_cb into runtime so state machine owns lifecycle.
auto & d = brain::runtime();
d.execute_fn = [this, goal_handle, skills](rclcpp::Logger logger) -> brain::CerebellumData::ExecResult {
@@ -1371,9 +1493,24 @@ bool CerebellumNode::ValidateAndParseGoal(
goal_handle->abort(res);
return false;
}
const std::string & raw = goal->action_name;
RCLCPP_INFO(logger, "[ExecuteBtAction] Received goal action_name=%s", raw.c_str());
skills_out = ParseSkillSequence(raw);
// Prefer new Plan-A payload path when calls are provided; fallback to legacy action_name
if (!goal->calls.empty()) {
skills_out.clear(); skills_out.reserve(goal->calls.size());
for (const auto & c : goal->calls) {
// Minimal loop: only use name to drive existing machinery (MoveWaist/MoveLeg first)
skills_out.push_back(c.name);
}
std::ostringstream oss; oss << "[ExecuteBtAction] Received goal calls=[";
for (size_t i = 0; i < goal->calls.size(); ++i) {
if (i) oss << ','; oss << goal->calls[i].name;
}
oss << "] (count=" << goal->calls.size() << ")";
RCLCPP_INFO(logger, "%s", oss.str().c_str());
} else {
const std::string & raw = goal->action_name;
RCLCPP_INFO(logger, "[ExecuteBtAction] Received goal action_name=%s", raw.c_str());
skills_out = ParseSkillSequence(raw);
}
if (skills_out.empty()) {
auto res = std::make_shared<EBA::Result>();
res->success = false;
@@ -1395,6 +1532,12 @@ bool CerebellumNode::ValidateAndParseGoal(
*/
std::string CerebellumNode::ResolveTopicForSkill(const std::string & skill) const
{
// Plan A minimal: if last_calls_ has a matching name with non-empty topic, use it
for (const auto & c : last_calls_) {
if (c.name == skill && !c.topic.empty()) {
return c.topic;
}
}
const std::string snake = ToSnake(skill);
if (action_clients_->has_client(snake)) {return snake;}
if (action_clients_->has_client(skill)) {return skill;}

View File

@@ -159,6 +159,15 @@ void CerebrumNode::RegisterActionClient()
}
}
g.action_name = oss.str();
// Populate per-skill calls[] using dynamic parameters
g.calls.clear();
if (single_skill_goal_override_) {
g.calls.push_back(BuildSkillCallForSkill(*single_skill_goal_override_));
} else {
for (const auto & s : current_sequence_skills_) {
g.calls.push_back(BuildSkillCallForSkill(s));
}
}
RCLCPP_INFO(this->get_logger(), "[ExecuteBtAction]Sending goal epoch=%u skills=%s",
g.epoch, g.action_name.c_str());
return g;
@@ -427,6 +436,8 @@ void CerebrumNode::RegisterSkillBtActions()
info.skill_name = skill.name;
info.last_progress = 0.0;
info.cancel_state = PerNodeExecInfo::CancelState::NONE;
// Ensure per-skill params are declared before send
DeclareBtActionParamsForSkill(skill.name);
// Override goal builder to send only this skill.
single_skill_goal_override_ = skill.name;
if (!action_registry_->wait_for_server(brain::kExecuteBtActionName, 1500ms)) {
@@ -480,6 +491,80 @@ void CerebrumNode::RegisterSkillBtActions()
}
}
void CerebrumNode::DeclareBtActionParamsForSkill(const std::string & skill_name)
{
// Declare a generic namespace for each skill to allow configuring routing/topic and payload
// Example params:
// cerebrum.bt.<Skill>.topic (string)
// cerebrum.bt.<Skill>.payload_yaml (string)
const std::string ns = std::string("cerebrum.bt.") + skill_name + ".";
const std::string p_topic = ns + "topic";
const std::string p_payload = ns + "payload_yaml";
if (!this->has_parameter(p_topic)) {
this->declare_parameter<std::string>(p_topic, std::string(""));
}
if (!this->has_parameter(p_payload)) {
this->declare_parameter<std::string>(p_payload, std::string(""));
}
// Seed example payload for selected skills to ease testing
try {
auto current = this->get_parameter(p_payload).as_string();
if (current.empty()) {
std::string sample;
if (skill_name == "MoveWaist") {
sample = "move_pitch_degree: 8.0\nmove_yaw_degree: -12.0\n";
} else if (skill_name == "MoveLeg") {
sample = "move_up_distance: 0.06\n";
} else if (skill_name == "MoveWheel") {
sample = "move_distance: 0.50\nmove_angle: 15.0\n";
} else if (skill_name == "MoveHome") {
// MoveHome goal is empty; seed explicit empty map for clarity
sample = "{}\n";
}
if (!sample.empty()) {
this->set_parameter(rclcpp::Parameter(p_payload, sample));
RCLCPP_INFO(this->get_logger(), "[Cerebrum] Seeded sample payload for %s", skill_name.c_str());
}
}
} catch (const std::exception & e) {
RCLCPP_WARN(this->get_logger(), "[%s] seeding sample payload failed: %s", skill_name.c_str(), e.what());
}
}
brain_interfaces::msg::SkillCall CerebrumNode::BuildSkillCallForSkill(const std::string & skill_name) const
{
brain_interfaces::msg::SkillCall call;
call.name = skill_name;
// Interface type/kind inference from SkillSpec
if (!skill_manager_) {return call;}
auto it = skill_manager_->skills().find(skill_name);
if (it != skill_manager_->skills().end() && !it->second.interfaces.empty()) {
// Use first interface as primary
const std::string & iface = it->second.interfaces.front();
call.interface_type = iface;
auto pos = iface.rfind('.');
std::string kind = (pos == std::string::npos) ? std::string{} : iface.substr(pos + 1);
for (auto & c : kind) c = static_cast<char>(::tolower(static_cast<unsigned char>(c)));
if (kind == "srv") kind = "service";
call.call_kind = kind;
}
// Read dynamic params
const std::string ns = std::string("cerebrum.bt.") + skill_name + ".";
const std::string p_topic = ns + "topic";
const std::string p_payload = ns + "payload_yaml";
try {
if (this->has_parameter(p_topic)) {
call.topic = this->get_parameter(p_topic).as_string();
}
if (this->has_parameter(p_payload)) {
call.payload_yaml = this->get_parameter(p_payload).as_string();
}
} catch (const std::exception & e) {
RCLCPP_WARN(this->get_logger(), "[%s] read params failed: %s", skill_name.c_str(), e.what());
}
return call;
}
/**
* @brief Randomly select up to count distinct action-capable skills (respecting whitelist).
* @param count Maximum number of skills.

View File

@@ -18,6 +18,7 @@ find_package(interfaces REQUIRED)
set(msg_files
msg/Movej.msg
msg/SkillCall.msg
)
set(action_files
action/ExecuteBtAction.action

View File

@@ -29,6 +29,7 @@
# server can reject stale goals and stop publishing feedback from older epochs.
uint32 epoch
string action_name
brain_interfaces/SkillCall[] calls
---
# Result

View File

@@ -0,0 +1,6 @@
# Generic skill call descriptor for ExecuteBtAction (scheme A)
string name # Skill name, e.g., "MoveWaist" / "MoveLeg"
string interface_type # e.g., "interfaces/action/MoveWaist" or "interfaces/srv/VisionObjectRecognition"
string call_kind # "action" | "srv"
string topic # optional topic/service override; empty => use defaults/parameters
string payload_yaml # YAML string of Goal/Request fields; may be empty for default goal