-
Notifications
You must be signed in to change notification settings - Fork 479
Open
Labels
more-information-neededFurther information is requiredFurther information is required
Description
Bug report
Required Info:
- Operating System:
- Ubuntu 20.04
- Installation type:
- from source
- Version or commit hash:
- iron
- DDS implementation:
- Cyclone dds
- Client library (if applicable):
- rclcpp_action
Steps to reproduce issue
I am do stress test for action server and catch this error on random request. How i can fix that?
using Exec = devicelib_msgs::action::Exec;
using GoalHandle = rclcpp_action::ServerGoalHandle<Exec>;
class Server final : public rclcpp::Node {
public:
Server() : rclcpp::Node("action_server") {
using namespace std::placeholders;
m_cb = create_callback_group(rclcpp::CallbackGroupType::Reentrant);
m_server = rclcpp_action::create_server<Exec>(
this,
"/test/server",
std::bind(&Server::goalHandle, this, _1, _2),
std::bind(&Server::handleCancel, this, _1),
std::bind(&Server::handleAccepted, this, _1),
rcl_action_server_get_default_options(),
m_cb
);
}
Server(Server const &) = delete;
Server(Server &&) noexcept = delete;
Server& operator=(Server const &) = delete;
Server& operator=(Server &&) noexcept = delete;
~Server() noexcept = default;
private:
rclcpp_action::GoalResponse goalHandle(rclcpp_action::GoalUUID const &uuid,
Exec::Goal::ConstSharedPtr goal) {
RCLCPP_INFO_STREAM(get_logger(), "Goal handle");
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
}
rclcpp_action::CancelResponse handleCancel(std::shared_ptr<GoalHandle> const goalHandle) {
RCLCPP_INFO_STREAM(get_logger(), "Handle cancel");
return rclcpp_action::CancelResponse::ACCEPT;
}
void handleAccepted(std::shared_ptr<GoalHandle> const goalHandle) {
RCLCPP_INFO_STREAM(get_logger(), "Handle accepted");
std::thread([goal = goalHandle, this] () -> void {
this->execute(std::move(goal));
}).detach();
}
void execute(std::shared_ptr<GoalHandle> const goalHandle) {
RCLCPP_INFO_STREAM(get_logger(), "Start execute");
auto const goal = goalHandle->get_goal();
auto const feedback = std::make_shared<Exec::Feedback>();
auto const result = std::make_shared<Exec::Result>();
size_t counter = 0;
for (auto const &_: goal->details) {
if (goalHandle->is_canceling()) {
result->message = "Canceled by peer";
goalHandle->canceled(result);
RCLCPP_INFO(get_logger(), "Goal canceled");
return;
}
RCLCPP_INFO_STREAM(get_logger(), "Start detail: " << counter);
std::this_thread::sleep_for(std::chrono::milliseconds(100));
feedback->num_executed_details = counter;
feedback->command_status.command_name = "command";
counter++;
feedback->command_status.seconds = goal->details.size() - counter;
goalHandle->publish_feedback(feedback);
RCLCPP_INFO_STREAM(get_logger(), "Publish feedback");
}
if (rclcpp::ok()) {
goalHandle->succeed(result);
RCLCPP_INFO_STREAM(get_logger(), "Goal success");
}
}
private:
rclcpp_action::Server<Exec>::SharedPtr m_server;
rclcpp::CallbackGroup::SharedPtr m_cb;
};
int main(int argc, char** argv) {
rclcpp::init(argc, argv);
auto const server = std::make_shared<Server>();
rclcpp::executors::MultiThreadedExecutor executor;
executor.add_node(server);
executor.spin();
rclcpp::shutdown();
}
Expected behavior
Normal client/server action behavior where each client sends a goal and receives a result from the server.
Actual behavior
Node Server throws an exception and crashes
terminate called after throwing an instance of 'std::runtime_error'
what(): Executing action server but nothing is ready
Additional information
Feature request
Feature description
Implementation considerations
Metadata
Metadata
Assignees
Labels
more-information-neededFurther information is requiredFurther information is required