onFeedback for bt_action_node is not receiving feedback
When creating a custom RosActionNode and overriding the onFeedback method, the method is never called. Here is an example: The .hpp file
#pragma once
#include <behaviortree_ros2/bt_action_node.hpp>
#include <iostream>
#include "behaviortree_cpp/action_node.h"
#include "dictator_behavior_tree/pose_to_string.hpp"
#include "geometry_msgs/msg/pose.hpp"
#include "nav2_msgs/action/navigate_to_pose.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
using Nav2 = nav2_msgs::action::NavigateToPose;
namespace BT
{
class NavigateToPose : public RosActionNode<Nav2>
{
public:
NavigateToPose(const std::string &name, const NodeConfig &conf, const RosNodeParams ¶ms)
: RosActionNode<Nav2>(name, conf, params)
{
}
static PortsList providedPorts()
{
return providedBasicPorts({InputPort<Position2D>("goal_pose")});
}
bool setGoal(RosActionNode::Goal &goal) override;
NodeStatus onResultReceived(const WrappedResult &wr) override;
NodeStatus onFailure(ActionNodeErrorCode error) override;
NodeStatus onFeedback(const std::shared_ptr<const Feedback> feedback) override;
};
} // namespace BT
the implemented method:
NodeStatus NavigateToPose::onFeedback(const std::shared_ptr<const Feedback> feedback)
{
std::cout << "FEEDBACK" << std::endl;
std::stringstream ss;
ss << "Estimated remaining time: " << feedback->estimated_time_remaining.sec << " ";
std::cout << ss.str() << std::endl;
return NodeStatus::RUNNING;
}
With this example, I never get an output to the terminal for the received feedback. I also validated that the action does provide a feedback by listening to the action feedback topic ros2 topic echo /navigate_to_pose/_action/feedback
Thanks for reporting, I will have a look
i have same issue, I've done echo topic on feedback action and the results come out, but onFeedback doesn't get called
我的程序同样无法接收到反馈,事实上,它完全没有进入onFeedback函数
class FibonacciAction final : public BT::RosActionNode<action_tutorials_interfaces::action::Fibonacci>
{
public:
FibonacciAction(const std::string_view name,
const BT::NodeConfig& config,
const BT::RosNodeParams& params)
: BT::RosActionNode<action_tutorials_interfaces::action::Fibonacci>(name.data(), config, params) { }
bool setGoal(RosActionNode::Goal& goal) override
{
int x;
std::cout << "请输入:";
std::cin >> x;
goal.order = x;
return true;
}
BT::NodeStatus onResultReceived(const WrappedResult& wr) override
{
std::stringstream ss;
ss << "Result received: ";
for (auto number : wr.result->sequence) {
ss << number << " ";
}
RCLCPP_INFO(node_->get_logger(), ss.str().c_str());
return BT::NodeStatus::SUCCESS;
}
BT::NodeStatus onFailure(BT::ActionNodeErrorCode error) override
{
RCLCPP_ERROR(node_->get_logger(), "Error: %s", BT::toStr(error));
return BT::NodeStatus::FAILURE;
}
BT::NodeStatus onFeedback(const std::shared_ptr<const action_tutorials_interfaces::action::Fibonacci::Feedback> feedback) override
{
std::stringstream ss;
ss << "Next number in sequence received: ";
for (auto number : feedback->partial_sequence) {
ss << number << " ";
}
RCLCPP_INFO(node_->get_logger(), ss.str().c_str());
return BT::NodeStatus::FAILURE;
}
};
static const char* xml_text = R"(
<root BTCPP_format="4" >
<BehaviorTree ID="MainTree">
<Sequence name="root_sequence">
<Fibonacci action_name="fibonacci"/>
</Sequence>
</BehaviorTree>
</root>
)";
auto main(int argc, char** argv) -> int
{
rclcpp::init(argc, argv);
BT::BehaviorTreeFactory factory;
auto node = std::make_shared<rclcpp::Node>("client");
BT::RosNodeParams params;
params.nh = node;
params.default_port_value = "fibonacci";
factory.registerNodeType<FibonacciAction>("Fibonacci", params);
auto tree = factory.createTreeFromText(xml_text);
tree.tickWhileRunning();
return 0;
}
我使用的ros2版本是humble,当我使用ros2 action send_goal -f指令时,可以得到上述代码给出的feed back
I have the same issue, onFeedback doesn't get called and Tree doesnt return RUNNING As Status. Did someone find a solution for this?