-
Couldn't load subscription status.
- Fork 475
Closed
Labels
Description
Question
Required Info:
- Operating System:
- Ubuntu 20.04
- Installation type:
- binaries
- Version or commit hash:
- foxy
- DDS implementation:
- Fast-DDS
- Client library (if applicable):
- rclcpp_lifecycle
Steps to reproduce issue
I just learned ros2 recently and am learning to use lifecycle node.
When I execute the trigger_transition(Transition::TRANSITION_DEACTIVATE);in the timer callback function,I will get the following error report:
string capacity not greater than size
[ERROR] [1653388415.412117081] []: Unable to start transition 4 from current state deactivating: Could not publish transition: cannot publish data, at /tmp/binarydeb/ros-foxy-rmw-fastrtps-shared-cpp-1.3.0/src/rmw_publish.cpp:55, at /tmp/binarydeb/ros-foxy-rcl-1.1.13/src/rcl/publisher.c:319, at /tmp/binarydeb/ros-foxy-rcl-lifecycle-1.1.13/src/rcl_lifecycle.c:367
And my node state will always be deactivating, can no longer be changed
Here are some of my code:
rclcpp::TimerBase::SharedPtr m_timer = create_wall_timer(500ms, std::bind(&TestLifecycleNode::onTimerCb, this));
void TestLifecycleNode::onTimerCb() {
auto nodes = this->get_node_graph_interface()->get_node_names();
map<string, uint8_t>::iterator it = m_parents_state.begin();
while (it != m_parents_state.end()) {
string name = it->first;
uint8_t state = it->second;
if (std::find(nodes.begin(), nodes.end(), name) == nodes.end()) {
RCLCPP_INFO(get_logger(),
"Parent %s is not longer present, removing from parent nodes container",
name.c_str());
it = m_parents_state.erase(it);
if (state == State::PRIMARY_STATE_ACTIVE && m_parents_state.empty())
trigger_transition(Transition::TRANSITION_DEACTIVATE);
}
else
it++;
}
}
But when I execute the trigger_transition(Transition::TRANSITION_DEACTIVATE); in the message callback function,It will be all right.Here are some of my code:
rclcpp::Subscription<NodeBinding>::SharedPtr m_binding_subscriber =
create_subscription<NodeBinding>(
"test_binding", rclcpp::QoS(1000).keep_all().transient_local().reliable(),
std::bind(&TestLifecycleNode::onNodeBindingCb, this, _1));
void TestLifecycleNode::onNodeBindingCb(const NodeBinding::SharedPtr msg) {
if (msg->child_node == get_name() && m_parents_state.count(msg->parent_node) > 0) {
uint8_t remover_state = m_parents_state[msg->parent_node];
m_parents_state.erase(msg->parent_node);
if(remover_state == State::PRIMARY_STATE_ACTIVE && m_parents_state.empty())
trigger_transition(Transition::TRANSITION_DEACTIVATE);
}
}
Above, I would like to ask what I did wrong? Or is this a bug?
I'm looking forward to someone's help. This problem has bothered me for a long time.Thanks