Message doesn't leave scope of node, if beeing sent in constructor
Hello, I'm facing a problem, which I can't seem to find any solution for.
Following situation: I'm trying to communicate with multiple vehicles (for prototyping I'm using differenct computers) in one network. I reduced my code to the absolute minimal to show you the problem. The code is the exact same on both of the computers, execpt from the uid_ in the header, which is different.
Steps to reproduce:
- Start node at one computer
- Start other note at the other comptuer
Expected result:
- When starting the second node the callback should show the message on topic /u2u/election at both computers
Actual Result:
- Well, it doesn't show up on the first computer, but only on the one where the node was started from
Other things I tried to debug the problem:
- When opening an extra terminal and echoing the topic with
ros2 topic echo /u2u/election
the message sometimes pops up and sometimes it doesn't. This applys for both computers, the one where the node is started and the other one. It seems to be random. - When publishing a message manually via command line the message is received by both terminals echoing the topic and by both nodes
Thanks for your time and let me know if you need any additional information!
u2u_link_minimal.cpp
// include the header of this class
#include "u2u_link/u2u_link_mini.hpp"
/*******************************************************************************************************************//**
* @brief Constructor of the ROS node, inherit from Node. Here all ROS specific initializations are done
***********************************************************************************************************************/
U2uLink::U2uLink() : Node("u2u_link")
{
// Publisher
init_publisher();
// Subscriber
init_subscriber();
start_election();
// Initialization of node
RCLCPP_INFO(this->get_logger(), "Startup init of " + node_name_ + " finished");
}
/*******************************************************************************************************************//**
* @brief Destructor
***********************************************************************************************************************/
U2uLink::~U2uLink()
{
}
/*******************************************************************************************************************//**
* @brief This method initializes the ROS publisher
***********************************************************************************************************************/
void U2uLink::init_publisher()
{
pub_elect_u2u_ = this->create_publisher<std_msgs::msg::UInt16>("/u2u/election", 10);
}
/*******************************************************************************************************************//**
* @brief This method initializes the ROS subscriber
***********************************************************************************************************************/
void U2uLink::init_subscriber()
{
sub_elect_u2u_ = this->create_subscription<std_msgs::msg::UInt16>("/u2u/election", 1,
bind(&U2uLink::sub_elect_u2u_cb, this,
placeholders::_1));
}
/*******************************************************************************************************************//**
* @brief This method initializes the connection to other UAVs
***********************************************************************************************************************/
void U2uLink::start_election()
{
auto msg = std_msgs::msg::UInt16();
msg.data = uid_;
pub_elect_u2u_ -> publish(msg);
}
/*******************************************************************************************************************//**
* @brief Subscriber callback for /u2u/election
* @param common::msg::UInt16::SharedPtr
***********************************************************************************************************************/
void U2uLink::sub_elect_u2u_cb(const std_msgs::msg::UInt16::SharedPtr msg)
{
cout << msg->data << "received in cb " << endl;
}
/*******************************************************************************************************************//**
* @brief the main function which initializes and starts the node object
* @param int argument count, char ** argument values
* @return exit code
***********************************************************************************************************************/
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
rclcpp::executors::MultiThreadedExecutor executor;
auto n = std::make_shared<U2uLink>();
executor.add_node(n);
executor.spin();
rclcpp::shutdown();
return 0;
}
u2u_link_minimal.hpp
#ifndef U2U_LINK_MINI_HPP
#define U2U_LINK_MINI_HPP
// C system header
#include <stdint.h>
// C++ STL header
#include <iostream>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/u_int16.hpp"
// usings
using namespace std;
class U2uLink : public rclcpp::Node
{
public:
// Con-/De-structor
U2uLink();
~U2uLink();
private:
// General methods
void init_publisher();
void init_subscriber();
void start_election();
// Subsriber callbacks
void sub_elect_u2u_cb(const std_msgs::msg::UInt16::SharedPtr msg);
// Callback groups
rclcpp::callback_group::CallbackGroup::SharedPtr cb_group_clt_;
// Publisher
rclcpp::Publisher<std_msgs::msg::UInt16>::SharedPtr pub_elect_u2u_;
// Subscriber
rclcpp::Subscription<std_msgs::msg::UInt16>::SharedPtr sub_elect_u2u_;
// General variables
string node_name_ = "u2u_link";
uint16_t uid_ = 1002;
};
#endif