|
|
|
|
@@ -92,76 +92,15 @@ CerebellumNode::CerebellumNode(const rclcpp::NodeOptions & options)
|
|
|
|
|
#endif
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
void CerebellumNode::ConfigureActionHooks()
|
|
|
|
|
/**
|
|
|
|
|
* @brief Configure action hooks for arm control.
|
|
|
|
|
*
|
|
|
|
|
*/
|
|
|
|
|
void CerebellumNode::ConfigureArmHooks()
|
|
|
|
|
{
|
|
|
|
|
if (!skill_manager_) {
|
|
|
|
|
RCLCPP_WARN(this->get_logger(), "SkillManager 不可用,跳过动作钩子配置");
|
|
|
|
|
return;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
auto log_goal_response = [this](const std::string & skill_name, bool accepted, const std::string & action_name) {
|
|
|
|
|
if (accepted) {
|
|
|
|
|
RCLCPP_INFO(this->get_logger(), "[%s] %s goal 已被服务器接收", skill_name.c_str(), action_name.c_str());
|
|
|
|
|
} else {
|
|
|
|
|
RCLCPP_WARN(this->get_logger(), "[%s] %s goal 被服务器拒绝", skill_name.c_str(), action_name.c_str());
|
|
|
|
|
}
|
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
// ArmSpaceControl
|
|
|
|
|
SkillManager::ActionHookOptions<interfaces::action::ArmSpaceControl> arm_sc_hooks;
|
|
|
|
|
arm_sc_hooks.make_goal = [this](const std::string & skill_name) {
|
|
|
|
|
interfaces::action::ArmSpaceControl::Goal goal{};
|
|
|
|
|
const std::string param = "arm_space_control.reference_frame";
|
|
|
|
|
if (!this->has_parameter(param)) {
|
|
|
|
|
this->declare_parameter<std::string>(param, std::string("base_link"));
|
|
|
|
|
}
|
|
|
|
|
const auto frame = this->get_parameter(param).as_string();
|
|
|
|
|
RCLCPP_INFO(this->get_logger(), "[%s] ArmSpaceControl 使用参考坐标系 %s",
|
|
|
|
|
skill_name.c_str(), frame.c_str());
|
|
|
|
|
(void)frame;
|
|
|
|
|
//TODO :
|
|
|
|
|
goal.target.pose.position.x = 0.5;
|
|
|
|
|
goal.target.pose.position.y = 0.6;
|
|
|
|
|
goal.target.pose.position.z = 0.7;
|
|
|
|
|
return goal;
|
|
|
|
|
};
|
|
|
|
|
arm_sc_hooks.on_feedback = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
ActionClientRegistry::GoalHandle<interfaces::action::ArmSpaceControl>::SharedPtr,
|
|
|
|
|
const std::shared_ptr<const interfaces::action::ArmSpaceControl::Feedback> & feedback) {
|
|
|
|
|
if (!feedback) {
|
|
|
|
|
RCLCPP_WARN(this->get_logger(), "[%s] ArmSpaceControl feedback 为空", skill_name.c_str());
|
|
|
|
|
return;
|
|
|
|
|
}
|
|
|
|
|
(void)feedback;
|
|
|
|
|
//TODO :
|
|
|
|
|
RCLCPP_INFO(this->get_logger(), "[%s] Current progress: %.2f", skill_name.c_str(), feedback->progress);
|
|
|
|
|
|
|
|
|
|
};
|
|
|
|
|
arm_sc_hooks.on_result = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const ActionClientRegistry::GoalHandle<interfaces::action::ArmSpaceControl>::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] ArmSpaceControl 完成: %s", skill_name.c_str(), message.c_str());
|
|
|
|
|
} else if (res.code == rclcpp_action::ResultCode::CANCELED) {
|
|
|
|
|
RCLCPP_WARN(this->get_logger(), "[%s] ArmSpaceControl 被取消", skill_name.c_str());
|
|
|
|
|
} else {
|
|
|
|
|
RCLCPP_ERROR(this->get_logger(), "[%s] ArmSpaceControl 失败 (code=%d): %s",
|
|
|
|
|
skill_name.c_str(), static_cast<int>(res.code), message.c_str());
|
|
|
|
|
}
|
|
|
|
|
};
|
|
|
|
|
arm_sc_hooks.on_goal_response = [log_goal_response](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const std::shared_ptr<ActionClientRegistry::GoalHandle<interfaces::action::ArmSpaceControl>> & handle) {
|
|
|
|
|
log_goal_response(skill_name, static_cast<bool>(handle), "ArmSpaceControl");
|
|
|
|
|
};
|
|
|
|
|
skill_manager_->configure_action_hooks<interfaces::action::ArmSpaceControl>("ArmSpaceControl", std::move(arm_sc_hooks));
|
|
|
|
|
|
|
|
|
|
// Arm
|
|
|
|
|
SkillManager::ActionHookOptions<interfaces::action::Arm> arm_hooks;
|
|
|
|
|
arm_hooks.make_goal = [this](const std::string & skill_name) {
|
|
|
|
|
SkillManager::ActionHookOptions<interfaces::action::Arm> hooks;
|
|
|
|
|
hooks.make_goal = [this](const std::string & skill_name) {
|
|
|
|
|
interfaces::action::Arm::Goal 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
|
|
|
|
|
@@ -218,7 +157,7 @@ void CerebellumNode::ConfigureActionHooks()
|
|
|
|
|
|
|
|
|
|
return goal;
|
|
|
|
|
};
|
|
|
|
|
arm_hooks.on_feedback = [this](
|
|
|
|
|
hooks.on_feedback = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
ActionClientRegistry::GoalHandle<interfaces::action::Arm>::SharedPtr,
|
|
|
|
|
const std::shared_ptr<const interfaces::action::Arm::Feedback> & feedback) {
|
|
|
|
|
@@ -232,7 +171,7 @@ void CerebellumNode::ConfigureActionHooks()
|
|
|
|
|
skill_name.c_str(), feedback->command_id, feedback->int_lenth);
|
|
|
|
|
|
|
|
|
|
};
|
|
|
|
|
arm_hooks.on_result = [this](
|
|
|
|
|
hooks.on_result = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const ActionClientRegistry::GoalHandle<interfaces::action::Arm>::WrappedResult & res) {
|
|
|
|
|
const bool success = (res.code == rclcpp_action::ResultCode::SUCCEEDED && res.result && res.result->result == 0);
|
|
|
|
|
@@ -246,28 +185,39 @@ void CerebellumNode::ConfigureActionHooks()
|
|
|
|
|
skill_name.c_str(), static_cast<int>(res.code), message.c_str());
|
|
|
|
|
}
|
|
|
|
|
};
|
|
|
|
|
arm_hooks.on_goal_response = [log_goal_response](
|
|
|
|
|
hooks.on_goal_response = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const std::shared_ptr<ActionClientRegistry::GoalHandle<interfaces::action::Arm>> & handle) {
|
|
|
|
|
log_goal_response(skill_name, static_cast<bool>(handle), "Arm");
|
|
|
|
|
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::Arm>("Arm", std::move(arm_hooks));
|
|
|
|
|
skill_manager_->configure_action_hooks<interfaces::action::Arm>("Arm", std::move(hooks));
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* @brief Configure action hooks for hand control.
|
|
|
|
|
*
|
|
|
|
|
*/
|
|
|
|
|
void CerebellumNode::ConfigureHandControlHooks()
|
|
|
|
|
{
|
|
|
|
|
// HandControl
|
|
|
|
|
SkillManager::ActionHookOptions<interfaces::action::HandControl> hand_hooks;
|
|
|
|
|
hand_hooks.make_goal = [this](const std::string & skill_name) {
|
|
|
|
|
SkillManager::ActionHookOptions<interfaces::action::HandControl> hooks;
|
|
|
|
|
hooks.make_goal = [this](const std::string & skill_name) {
|
|
|
|
|
interfaces::action::HandControl::Goal 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});
|
|
|
|
|
}
|
|
|
|
|
const auto values = this->get_parameter(param).as_double_array();
|
|
|
|
|
RCLCPP_INFO(this->get_logger(), "[%s] HandControl 目标参数 size=%zu", skill_name.c_str(), values.size());
|
|
|
|
|
RCLCPP_INFO(this->get_logger(), "[%s] 目标参数 size=%zu", skill_name.c_str(), values.size());
|
|
|
|
|
(void)values;
|
|
|
|
|
goal.mode = 1;
|
|
|
|
|
return goal;
|
|
|
|
|
};
|
|
|
|
|
hand_hooks.on_feedback = [this](
|
|
|
|
|
hooks.on_feedback = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
ActionClientRegistry::GoalHandle<interfaces::action::HandControl>::SharedPtr,
|
|
|
|
|
const std::shared_ptr<const interfaces::action::HandControl::Feedback> & feedback) {
|
|
|
|
|
@@ -276,251 +226,258 @@ void CerebellumNode::ConfigureActionHooks()
|
|
|
|
|
//TODO :
|
|
|
|
|
RCLCPP_INFO(this->get_logger(), "[%s] Current progress: %.2f", skill_name.c_str(), feedback->progress);
|
|
|
|
|
};
|
|
|
|
|
hand_hooks.on_result = [this](
|
|
|
|
|
hooks.on_result = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const ActionClientRegistry::GoalHandle<interfaces::action::HandControl>::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] HandControl 成功: %s", skill_name.c_str(), message.c_str());
|
|
|
|
|
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] HandControl 被取消", skill_name.c_str());
|
|
|
|
|
RCLCPP_WARN(this->get_logger(), "[%s] 被取消", skill_name.c_str());
|
|
|
|
|
} else {
|
|
|
|
|
RCLCPP_ERROR(this->get_logger(), "[%s] HandControl 失败 (code=%d): %s",
|
|
|
|
|
RCLCPP_ERROR(this->get_logger(), "[%s] 失败 (code=%d): %s",
|
|
|
|
|
skill_name.c_str(), static_cast<int>(res.code), message.c_str());
|
|
|
|
|
}
|
|
|
|
|
};
|
|
|
|
|
hand_hooks.on_goal_response = [log_goal_response](
|
|
|
|
|
hooks.on_goal_response = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const std::shared_ptr<ActionClientRegistry::GoalHandle<interfaces::action::HandControl>> & handle) {
|
|
|
|
|
log_goal_response(skill_name, static_cast<bool>(handle), "HandControl");
|
|
|
|
|
};
|
|
|
|
|
skill_manager_->configure_action_hooks<interfaces::action::HandControl>("HandControl", std::move(hand_hooks));
|
|
|
|
|
|
|
|
|
|
// LegControl
|
|
|
|
|
SkillManager::ActionHookOptions<interfaces::action::LegControl> leg_hooks;
|
|
|
|
|
leg_hooks.make_goal = [this](const std::string & skill_name) {
|
|
|
|
|
interfaces::action::LegControl::Goal goal{};
|
|
|
|
|
const std::string param = "leg_control.speed_scale";
|
|
|
|
|
if (!this->has_parameter(param)) {
|
|
|
|
|
this->declare_parameter<double>(param, 1.0);
|
|
|
|
|
}
|
|
|
|
|
const auto scale = this->get_parameter(param).as_double();
|
|
|
|
|
RCLCPP_INFO(this->get_logger(), "[%s] LegControl speed_scale=%.2f", skill_name.c_str(), scale);
|
|
|
|
|
(void)scale;
|
|
|
|
|
return goal;
|
|
|
|
|
};
|
|
|
|
|
leg_hooks.on_feedback = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
ActionClientRegistry::GoalHandle<interfaces::action::LegControl>::SharedPtr,
|
|
|
|
|
const std::shared_ptr<const interfaces::action::LegControl::Feedback> & feedback) {
|
|
|
|
|
if (!feedback) {return;}
|
|
|
|
|
RCLCPP_INFO(this->get_logger(), "[%s] LegControl feedback 接收", skill_name.c_str());
|
|
|
|
|
(void)feedback;
|
|
|
|
|
};
|
|
|
|
|
leg_hooks.on_result = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const ActionClientRegistry::GoalHandle<interfaces::action::LegControl>::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] LegControl 成功: %s", skill_name.c_str(), message.c_str());
|
|
|
|
|
} else if (res.code == rclcpp_action::ResultCode::CANCELED) {
|
|
|
|
|
RCLCPP_WARN(this->get_logger(), "[%s] LegControl 被取消", skill_name.c_str());
|
|
|
|
|
if (static_cast<bool>(handle)) {
|
|
|
|
|
RCLCPP_INFO(this->get_logger(), "[%s] goal 已被服务器接收", skill_name.c_str());
|
|
|
|
|
} else {
|
|
|
|
|
RCLCPP_ERROR(this->get_logger(), "[%s] LegControl 失败 (code=%d): %s",
|
|
|
|
|
skill_name.c_str(), static_cast<int>(res.code), message.c_str());
|
|
|
|
|
RCLCPP_WARN(this->get_logger(), "[%s] goal 被服务器拒绝", skill_name.c_str());
|
|
|
|
|
}
|
|
|
|
|
};
|
|
|
|
|
leg_hooks.on_goal_response = [log_goal_response](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const std::shared_ptr<ActionClientRegistry::GoalHandle<interfaces::action::LegControl>> & handle) {
|
|
|
|
|
log_goal_response(skill_name, static_cast<bool>(handle), "LegControl");
|
|
|
|
|
};
|
|
|
|
|
skill_manager_->configure_action_hooks<interfaces::action::LegControl>("LegControl", std::move(leg_hooks));
|
|
|
|
|
|
|
|
|
|
// VisionGraspObject
|
|
|
|
|
SkillManager::ActionHookOptions<interfaces::action::VisionGraspObject> vision_hooks;
|
|
|
|
|
vision_hooks.make_goal = [this](const std::string & skill_name) {
|
|
|
|
|
interfaces::action::VisionGraspObject::Goal goal{};
|
|
|
|
|
const std::string target_param = "vision_grasp_object.target";
|
|
|
|
|
if (!this->has_parameter(target_param)) {
|
|
|
|
|
this->declare_parameter<std::string>(target_param, std::string("cup"));
|
|
|
|
|
}
|
|
|
|
|
const auto target = this->get_parameter(target_param).as_string();
|
|
|
|
|
RCLCPP_INFO(this->get_logger(), "[%s] VisionGraspObject target=%s",
|
|
|
|
|
skill_name.c_str(), target.c_str());
|
|
|
|
|
(void)target;
|
|
|
|
|
return goal;
|
|
|
|
|
};
|
|
|
|
|
vision_hooks.on_feedback = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
ActionClientRegistry::GoalHandle<interfaces::action::VisionGraspObject>::SharedPtr,
|
|
|
|
|
const std::shared_ptr<const interfaces::action::VisionGraspObject::Feedback> & feedback) {
|
|
|
|
|
if (!feedback) {return;}
|
|
|
|
|
RCLCPP_INFO(this->get_logger(), "[%s] VisionGraspObject feedback 接收", skill_name.c_str());
|
|
|
|
|
(void)feedback;
|
|
|
|
|
};
|
|
|
|
|
vision_hooks.on_result = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const ActionClientRegistry::GoalHandle<interfaces::action::VisionGraspObject>::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] VisionGraspObject 成功: %s", skill_name.c_str(), message.c_str());
|
|
|
|
|
} else if (res.code == rclcpp_action::ResultCode::CANCELED) {
|
|
|
|
|
RCLCPP_WARN(this->get_logger(), "[%s] VisionGraspObject 被取消", skill_name.c_str());
|
|
|
|
|
} else {
|
|
|
|
|
RCLCPP_ERROR(this->get_logger(), "[%s] VisionGraspObject 失败 (code=%d): %s",
|
|
|
|
|
skill_name.c_str(), static_cast<int>(res.code), message.c_str());
|
|
|
|
|
}
|
|
|
|
|
};
|
|
|
|
|
vision_hooks.on_goal_response = [log_goal_response](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const std::shared_ptr<ActionClientRegistry::GoalHandle<interfaces::action::VisionGraspObject>> & handle) {
|
|
|
|
|
log_goal_response(skill_name, static_cast<bool>(handle), "VisionGraspObject");
|
|
|
|
|
};
|
|
|
|
|
skill_manager_->configure_action_hooks<interfaces::action::VisionGraspObject>("VisionGraspObject", std::move(vision_hooks));
|
|
|
|
|
|
|
|
|
|
// SlamMode (mapping toggle)
|
|
|
|
|
SkillManager::ActionHookOptions<interfaces::action::SlamMode> slam_hooks;
|
|
|
|
|
slam_hooks.make_goal = [this](const std::string & skill_name) {
|
|
|
|
|
interfaces::action::SlamMode::Goal goal{};
|
|
|
|
|
const std::string param_name = "slam_mode.enable_mapping";
|
|
|
|
|
if (!this->has_parameter(param_name)) {
|
|
|
|
|
this->declare_parameter<bool>(param_name, slam_enable_mapping_default_);
|
|
|
|
|
}
|
|
|
|
|
goal.enable_mapping = this->get_parameter(param_name).as_bool();
|
|
|
|
|
RCLCPP_INFO(this->get_logger(), "[%s] SlamMode enable_mapping=%s",
|
|
|
|
|
skill_name.c_str(), goal.enable_mapping ? "true" : "false");
|
|
|
|
|
return goal;
|
|
|
|
|
};
|
|
|
|
|
slam_hooks.on_feedback = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
ActionClientRegistry::GoalHandle<interfaces::action::SlamMode>::SharedPtr,
|
|
|
|
|
const std::shared_ptr<const interfaces::action::SlamMode::Feedback> & feedback) {
|
|
|
|
|
if (!feedback) {return;}
|
|
|
|
|
RCLCPP_INFO(this->get_logger(), "[%s] SlamMode feedback 接收", skill_name.c_str());
|
|
|
|
|
};
|
|
|
|
|
slam_hooks.on_result = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const ActionClientRegistry::GoalHandle<interfaces::action::SlamMode>::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] SlamMode 成功: %s", skill_name.c_str(), message.c_str());
|
|
|
|
|
} else if (res.code == rclcpp_action::ResultCode::CANCELED) {
|
|
|
|
|
RCLCPP_WARN(this->get_logger(), "[%s] SlamMode 被取消", skill_name.c_str());
|
|
|
|
|
} else {
|
|
|
|
|
RCLCPP_ERROR(this->get_logger(), "[%s] SlamMode 失败 (code=%d): %s",
|
|
|
|
|
skill_name.c_str(), static_cast<int>(res.code), message.c_str());
|
|
|
|
|
}
|
|
|
|
|
};
|
|
|
|
|
slam_hooks.on_goal_response = [log_goal_response](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const std::shared_ptr<ActionClientRegistry::GoalHandle<interfaces::action::SlamMode>> & handle) {
|
|
|
|
|
log_goal_response(skill_name, static_cast<bool>(handle), "SlamMode");
|
|
|
|
|
};
|
|
|
|
|
skill_manager_->configure_action_hooks<interfaces::action::SlamMode>("SlamMode", std::move(slam_hooks));
|
|
|
|
|
|
|
|
|
|
// NavigateToPose
|
|
|
|
|
SkillManager::ActionHookOptions<nav2_msgs::action::NavigateToPose> nav_hooks;
|
|
|
|
|
nav_hooks.make_goal = [this](const std::string & skill_name) {
|
|
|
|
|
nav2_msgs::action::NavigateToPose::Goal goal{};
|
|
|
|
|
const std::string pose_param = "navigate_to_pose.default_goal";
|
|
|
|
|
const std::string frame_param = "navigate_to_pose.goal_frame";
|
|
|
|
|
if (!this->has_parameter(pose_param)) {
|
|
|
|
|
this->declare_parameter<std::vector<double>>(pose_param, {0.0, 0.0, 0.0});
|
|
|
|
|
}
|
|
|
|
|
if (!this->has_parameter(frame_param)) {
|
|
|
|
|
this->declare_parameter<std::string>(frame_param, "map");
|
|
|
|
|
}
|
|
|
|
|
std::vector<double> coords;
|
|
|
|
|
try {
|
|
|
|
|
coords = this->get_parameter(pose_param).as_double_array();
|
|
|
|
|
} catch (const rclcpp::ParameterTypeException &)
|
|
|
|
|
{
|
|
|
|
|
coords = {0.0, 0.0, 0.0};
|
|
|
|
|
RCLCPP_WARN(this->get_logger(), "[%s] 参数 %s 应为 double 数组,使用默认 (0,0,0)",
|
|
|
|
|
skill_name.c_str(), pose_param.c_str());
|
|
|
|
|
}
|
|
|
|
|
const auto stamp = this->get_clock()->now();
|
|
|
|
|
goal.pose.header.stamp = stamp;
|
|
|
|
|
goal.pose.header.frame_id = this->get_parameter(frame_param).as_string();
|
|
|
|
|
if (coords.size() >= 2) {
|
|
|
|
|
goal.pose.pose.position.x = coords[0];
|
|
|
|
|
goal.pose.pose.position.y = coords[1];
|
|
|
|
|
}
|
|
|
|
|
double yaw = (coords.size() >= 3) ? coords[2] : 0.0;
|
|
|
|
|
yaw += nav_goal_yaw_offset_;
|
|
|
|
|
const double half = yaw * 0.5;
|
|
|
|
|
goal.pose.pose.orientation.w = std::cos(half);
|
|
|
|
|
goal.pose.pose.orientation.x = 0.0;
|
|
|
|
|
goal.pose.pose.orientation.y = 0.0;
|
|
|
|
|
goal.pose.pose.orientation.z = std::sin(half);
|
|
|
|
|
nav2_last_distance_remaining_.store(std::numeric_limits<double>::quiet_NaN(), std::memory_order_relaxed);
|
|
|
|
|
nav2_last_goal_succeeded_.store(false, std::memory_order_relaxed);
|
|
|
|
|
RCLCPP_INFO(this->get_logger(), "[%s] 导航目标 (%.2f, %.2f) yaw=%.2f (offset=%.2f)",
|
|
|
|
|
skill_name.c_str(), goal.pose.pose.position.x, goal.pose.pose.position.y, yaw, nav_goal_yaw_offset_);
|
|
|
|
|
return goal;
|
|
|
|
|
};
|
|
|
|
|
nav_hooks.on_feedback = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
ActionClientRegistry::GoalHandle<nav2_msgs::action::NavigateToPose>::SharedPtr,
|
|
|
|
|
const std::shared_ptr<const nav2_msgs::action::NavigateToPose::Feedback> & feedback) {
|
|
|
|
|
if (!feedback) {return;}
|
|
|
|
|
nav2_last_distance_remaining_.store(feedback->distance_remaining, std::memory_order_relaxed);
|
|
|
|
|
RCLCPP_INFO(this->get_logger(), "[%s] NavigateToPose feedback distance_remaining=%.2f",
|
|
|
|
|
skill_name.c_str(), feedback->distance_remaining);
|
|
|
|
|
};
|
|
|
|
|
nav_hooks.on_result = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const ActionClientRegistry::GoalHandle<nav2_msgs::action::NavigateToPose>::WrappedResult & res) {
|
|
|
|
|
const bool success = res.code == rclcpp_action::ResultCode::SUCCEEDED;
|
|
|
|
|
nav2_last_goal_succeeded_.store(success, std::memory_order_relaxed);
|
|
|
|
|
const double remaining = nav2_last_distance_remaining_.load(std::memory_order_relaxed);
|
|
|
|
|
if (success) {
|
|
|
|
|
if (std::isnan(remaining) || remaining <= nav_goal_distance_tolerance_) {
|
|
|
|
|
RCLCPP_INFO(this->get_logger(), "[%s] 导航完成,剩余距离=%.2f",
|
|
|
|
|
skill_name.c_str(), std::isnan(remaining) ? 0.0 : remaining);
|
|
|
|
|
} else {
|
|
|
|
|
RCLCPP_WARN(this->get_logger(), "[%s] 导航成功但剩余距离 %.2f 超过阈值 %.2f",
|
|
|
|
|
skill_name.c_str(), remaining, nav_goal_distance_tolerance_);
|
|
|
|
|
}
|
|
|
|
|
} else if (res.code == rclcpp_action::ResultCode::CANCELED) {
|
|
|
|
|
RCLCPP_WARN(this->get_logger(), "[%s] 导航被取消", skill_name.c_str());
|
|
|
|
|
} else if (res.code == rclcpp_action::ResultCode::ABORTED) {
|
|
|
|
|
RCLCPP_ERROR(this->get_logger(), "[%s] 导航失败 (ABORT)", skill_name.c_str());
|
|
|
|
|
} else {
|
|
|
|
|
RCLCPP_ERROR(this->get_logger(), "[%s] 导航失败 result_code=%d",
|
|
|
|
|
skill_name.c_str(), static_cast<int>(res.code));
|
|
|
|
|
}
|
|
|
|
|
};
|
|
|
|
|
nav_hooks.on_goal_response = [log_goal_response](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const std::shared_ptr<ActionClientRegistry::GoalHandle<nav2_msgs::action::NavigateToPose>> & handle) {
|
|
|
|
|
log_goal_response(skill_name, static_cast<bool>(handle), "NavigateToPose");
|
|
|
|
|
};
|
|
|
|
|
skill_manager_->configure_action_hooks<nav2_msgs::action::NavigateToPose>("NavigateToPose", std::move(nav_hooks));
|
|
|
|
|
skill_manager_->configure_action_hooks<interfaces::action::HandControl>("HandControl", std::move(hooks));
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
void CerebellumNode::ConfigureServiceHooks()
|
|
|
|
|
/**
|
|
|
|
|
* @brief Configure action hooks for waist movement.
|
|
|
|
|
*
|
|
|
|
|
*/
|
|
|
|
|
void CerebellumNode::ConfigureMoveWaistHooks()
|
|
|
|
|
{
|
|
|
|
|
// MoveWaist
|
|
|
|
|
SkillManager::ActionHookOptions<interfaces::action::MoveWaist> hooks;
|
|
|
|
|
hooks.make_goal = [this](const std::string & skill_name) {
|
|
|
|
|
interfaces::action::MoveWaist::Goal goal{};
|
|
|
|
|
//TODO
|
|
|
|
|
|
|
|
|
|
return goal;
|
|
|
|
|
};
|
|
|
|
|
hooks.on_feedback = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
ActionClientRegistry::GoalHandle<interfaces::action::MoveWaist>::SharedPtr,
|
|
|
|
|
const std::shared_ptr<const interfaces::action::MoveWaist::Feedback> & feedback) {
|
|
|
|
|
if (!feedback) {return;}
|
|
|
|
|
//TODO
|
|
|
|
|
|
|
|
|
|
};
|
|
|
|
|
hooks.on_result = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const ActionClientRegistry::GoalHandle<interfaces::action::MoveWaist>::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::MoveWaist>> & 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::MoveWaist>("MoveWaist", std::move(hooks));
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* @brief Configure action hooks for leg movement.
|
|
|
|
|
*
|
|
|
|
|
*/
|
|
|
|
|
void CerebellumNode::ConfigureMoveLegHooks()
|
|
|
|
|
{
|
|
|
|
|
// MoveLeg
|
|
|
|
|
SkillManager::ActionHookOptions<interfaces::action::MoveLeg> hooks;
|
|
|
|
|
hooks.make_goal = [this](const std::string & skill_name) {
|
|
|
|
|
interfaces::action::MoveLeg::Goal goal{};
|
|
|
|
|
//TODO
|
|
|
|
|
|
|
|
|
|
return goal;
|
|
|
|
|
};
|
|
|
|
|
hooks.on_feedback = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
ActionClientRegistry::GoalHandle<interfaces::action::MoveLeg>::SharedPtr,
|
|
|
|
|
const std::shared_ptr<const interfaces::action::MoveLeg::Feedback> & feedback) {
|
|
|
|
|
if (!feedback) {return;}
|
|
|
|
|
//TODO
|
|
|
|
|
|
|
|
|
|
};
|
|
|
|
|
hooks.on_result = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const ActionClientRegistry::GoalHandle<interfaces::action::MoveLeg>::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::MoveLeg>> & 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::MoveLeg>("MoveLeg", std::move(hooks));
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* @brief Configure action hooks for wheel movement.
|
|
|
|
|
*
|
|
|
|
|
*/
|
|
|
|
|
void CerebellumNode::ConfigureMoveWheelHooks()
|
|
|
|
|
{
|
|
|
|
|
// MoveWheel
|
|
|
|
|
SkillManager::ActionHookOptions<interfaces::action::MoveWheel> hooks;
|
|
|
|
|
hooks.make_goal = [this](const std::string & skill_name) {
|
|
|
|
|
interfaces::action::MoveWheel::Goal goal{};
|
|
|
|
|
//TODO
|
|
|
|
|
|
|
|
|
|
return goal;
|
|
|
|
|
};
|
|
|
|
|
hooks.on_feedback = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
ActionClientRegistry::GoalHandle<interfaces::action::MoveWheel>::SharedPtr,
|
|
|
|
|
const std::shared_ptr<const interfaces::action::MoveWheel::Feedback> & feedback) {
|
|
|
|
|
if (!feedback) {return;}
|
|
|
|
|
//TODO
|
|
|
|
|
|
|
|
|
|
};
|
|
|
|
|
hooks.on_result = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const ActionClientRegistry::GoalHandle<interfaces::action::MoveWheel>::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::MoveWheel>> & 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::MoveWheel>("MoveWheel", std::move(hooks));
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* @brief Configure action hooks for home movement.
|
|
|
|
|
*
|
|
|
|
|
*/
|
|
|
|
|
void CerebellumNode::ConfigureMoveHomeHooks()
|
|
|
|
|
{
|
|
|
|
|
// MoveHome
|
|
|
|
|
SkillManager::ActionHookOptions<interfaces::action::MoveHome> hooks;
|
|
|
|
|
hooks.make_goal = [this](const std::string & skill_name) {
|
|
|
|
|
interfaces::action::MoveHome::Goal goal{};
|
|
|
|
|
//TODO
|
|
|
|
|
|
|
|
|
|
return goal;
|
|
|
|
|
};
|
|
|
|
|
hooks.on_feedback = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
ActionClientRegistry::GoalHandle<interfaces::action::MoveHome>::SharedPtr,
|
|
|
|
|
const std::shared_ptr<const interfaces::action::MoveHome::Feedback> & feedback) {
|
|
|
|
|
if (!feedback) {return;}
|
|
|
|
|
//TODO
|
|
|
|
|
|
|
|
|
|
};
|
|
|
|
|
hooks.on_result = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const ActionClientRegistry::GoalHandle<interfaces::action::MoveHome>::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::MoveHome>> & 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::MoveHome>("MoveHome", std::move(hooks));
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* @brief Configure action hooks for various movements.
|
|
|
|
|
*
|
|
|
|
|
*/
|
|
|
|
|
void CerebellumNode::ConfigureActionHooks()
|
|
|
|
|
{
|
|
|
|
|
if (!skill_manager_) {
|
|
|
|
|
RCLCPP_WARN(this->get_logger(), "SkillManager 不可用,跳过服务钩子配置");
|
|
|
|
|
RCLCPP_WARN(this->get_logger(), "SkillManager 不可用,跳过动作钩子配置");
|
|
|
|
|
return;
|
|
|
|
|
}
|
|
|
|
|
ConfigureArmHooks();
|
|
|
|
|
ConfigureHandControlHooks();
|
|
|
|
|
ConfigureMoveWaistHooks();
|
|
|
|
|
ConfigureMoveLegHooks();
|
|
|
|
|
ConfigureMoveWheelHooks();
|
|
|
|
|
ConfigureMoveHomeHooks();
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* @brief Configure action hooks for vision object recognition.
|
|
|
|
|
*
|
|
|
|
|
*/
|
|
|
|
|
void CerebellumNode::ConfigureVisionObjectRecognitionHooks()
|
|
|
|
|
{
|
|
|
|
|
using VisionSrv = interfaces::srv::VisionObjectRecognition;
|
|
|
|
|
{
|
|
|
|
|
SkillManager::ServiceHookOptions<VisionSrv> vision_hooks;
|
|
|
|
|
vision_hooks.wait_timeout = [](const std::string &) {
|
|
|
|
|
SkillManager::ServiceHookOptions<VisionSrv> hooks;
|
|
|
|
|
hooks.wait_timeout = [](const std::string &) {
|
|
|
|
|
return std::chrono::seconds(2);
|
|
|
|
|
};
|
|
|
|
|
vision_hooks.call_timeout = [](const std::string &) {
|
|
|
|
|
hooks.call_timeout = [](const std::string &) {
|
|
|
|
|
return std::chrono::seconds(5);
|
|
|
|
|
};
|
|
|
|
|
vision_hooks.make_request = [this](const std::string & skill_name) {
|
|
|
|
|
hooks.make_request = [this](const std::string & skill_name) {
|
|
|
|
|
(void)skill_name;
|
|
|
|
|
auto req = std::make_shared<VisionSrv::Request>();
|
|
|
|
|
const std::string param = "vision_object_recognition.camera_position";
|
|
|
|
|
@@ -530,7 +487,7 @@ void CerebellumNode::ConfigureServiceHooks()
|
|
|
|
|
req->camera_position = this->get_parameter(param).as_string();
|
|
|
|
|
return req;
|
|
|
|
|
};
|
|
|
|
|
vision_hooks.on_response = [this](
|
|
|
|
|
hooks.on_response = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const SkillManager::ServiceHookOptions<VisionSrv>::ClientPtr &,
|
|
|
|
|
const SkillManager::ServiceHookOptions<VisionSrv>::ResponsePtr & resp,
|
|
|
|
|
@@ -576,70 +533,21 @@ void CerebellumNode::ConfigureServiceHooks()
|
|
|
|
|
}
|
|
|
|
|
return true;
|
|
|
|
|
};
|
|
|
|
|
skill_manager_->configure_service_hooks<VisionSrv>("VisionObjectRecognition", std::move(vision_hooks));
|
|
|
|
|
skill_manager_->configure_service_hooks<VisionSrv>("VisionObjectRecognition", std::move(hooks));
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
using MapSaveSrv = interfaces::srv::MapSave;
|
|
|
|
|
{
|
|
|
|
|
SkillManager::ServiceHookOptions<MapSaveSrv> save_hooks;
|
|
|
|
|
save_hooks.wait_timeout = [](const std::string &) {
|
|
|
|
|
return std::chrono::seconds(2);
|
|
|
|
|
};
|
|
|
|
|
save_hooks.call_timeout = [](const std::string &) {
|
|
|
|
|
return std::chrono::seconds(10);
|
|
|
|
|
};
|
|
|
|
|
save_hooks.make_request = [this](const std::string &) {
|
|
|
|
|
auto req = std::make_shared<MapSaveSrv::Request>();
|
|
|
|
|
req->map_url = map_save_url_;
|
|
|
|
|
return req;
|
|
|
|
|
};
|
|
|
|
|
save_hooks.on_response = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const SkillManager::ServiceHookOptions<MapSaveSrv>::ClientPtr &,
|
|
|
|
|
const SkillManager::ServiceHookOptions<MapSaveSrv>::ResponsePtr & resp,
|
|
|
|
|
std::string & detail) {
|
|
|
|
|
const bool ok = resp && resp->success;
|
|
|
|
|
detail = resp ? resp->message : std::string("Null response");
|
|
|
|
|
if (ok) {
|
|
|
|
|
RCLCPP_INFO(this->get_logger(), "[%s] MapSave ok: %s", skill_name.c_str(), detail.c_str());
|
|
|
|
|
} else {
|
|
|
|
|
RCLCPP_WARN(this->get_logger(), "[%s] MapSave failed: %s", skill_name.c_str(), detail.c_str());
|
|
|
|
|
}
|
|
|
|
|
return ok;
|
|
|
|
|
};
|
|
|
|
|
skill_manager_->configure_service_hooks<MapSaveSrv>("MapSave", std::move(save_hooks));
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
using MapLoadSrv = interfaces::srv::MapLoad;
|
|
|
|
|
{
|
|
|
|
|
SkillManager::ServiceHookOptions<MapLoadSrv> load_hooks;
|
|
|
|
|
load_hooks.wait_timeout = [](const std::string &) {
|
|
|
|
|
return std::chrono::seconds(2);
|
|
|
|
|
};
|
|
|
|
|
load_hooks.call_timeout = [](const std::string &) {
|
|
|
|
|
return std::chrono::seconds(10);
|
|
|
|
|
};
|
|
|
|
|
load_hooks.make_request = [this](const std::string &) {
|
|
|
|
|
auto req = std::make_shared<MapLoadSrv::Request>();
|
|
|
|
|
req->map_url = map_load_url_;
|
|
|
|
|
return req;
|
|
|
|
|
};
|
|
|
|
|
load_hooks.on_response = [this](
|
|
|
|
|
const std::string & skill_name,
|
|
|
|
|
const SkillManager::ServiceHookOptions<MapLoadSrv>::ClientPtr &,
|
|
|
|
|
const SkillManager::ServiceHookOptions<MapLoadSrv>::ResponsePtr & resp,
|
|
|
|
|
std::string & detail) {
|
|
|
|
|
const bool ok = resp && resp->success;
|
|
|
|
|
detail = resp ? resp->message : std::string("Null response");
|
|
|
|
|
if (ok) {
|
|
|
|
|
RCLCPP_INFO(this->get_logger(), "[%s] MapLoad ok: %s", skill_name.c_str(), detail.c_str());
|
|
|
|
|
} else {
|
|
|
|
|
RCLCPP_WARN(this->get_logger(), "[%s] MapLoad failed: %s", skill_name.c_str(), detail.c_str());
|
|
|
|
|
}
|
|
|
|
|
return ok;
|
|
|
|
|
};
|
|
|
|
|
skill_manager_->configure_service_hooks<MapLoadSrv>("MapLoad", std::move(load_hooks));
|
|
|
|
|
/**
|
|
|
|
|
* @brief Configure Service hooks for various movements.
|
|
|
|
|
*
|
|
|
|
|
*/
|
|
|
|
|
void CerebellumNode::ConfigureServiceHooks()
|
|
|
|
|
{
|
|
|
|
|
if (!skill_manager_) {
|
|
|
|
|
RCLCPP_WARN(this->get_logger(), "SkillManager 不可用,跳过服务钩子配置");
|
|
|
|
|
return;
|
|
|
|
|
}
|
|
|
|
|
ConfigureVisionObjectRecognitionHooks();
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
|