Skip to content

Commit

Permalink
Add initial_topic_ variable to avoid confusion
Browse files Browse the repository at this point in the history
This addresses comment
#106 (comment)

Signed-off-by: Rufus Wong <[email protected]>
  • Loading branch information
rcywongaa committed Jun 13, 2024
1 parent 31f49ae commit 867567e
Show file tree
Hide file tree
Showing 4 changed files with 10 additions and 6 deletions.
1 change: 1 addition & 0 deletions topic_tools/include/topic_tools/demux_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@ class DemuxNode final : public ToolBaseNode
const std::shared_ptr<topic_tools_interfaces::srv::DemuxSelect::Request> request,
std::shared_ptr<topic_tools_interfaces::srv::DemuxSelect::Response> response);

std::string initial_topic_;
std::vector<std::string> output_topics_;
rclcpp::Service<topic_tools_interfaces::srv::DemuxAdd>::SharedPtr demux_add_srv_;
rclcpp::Service<topic_tools_interfaces::srv::DemuxDelete>::SharedPtr demux_delete_srv_;
Expand Down
1 change: 1 addition & 0 deletions topic_tools/include/topic_tools/mux_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@ class MuxNode final : public ToolBaseNode
const std::shared_ptr<topic_tools_interfaces::srv::MuxSelect::Request> request,
std::shared_ptr<topic_tools_interfaces::srv::MuxSelect::Response> response);

std::string initial_topic_;
std::vector<std::string> input_topics_;
rclcpp::Service<topic_tools_interfaces::srv::MuxAdd>::SharedPtr mux_add_srv_;
rclcpp::Service<topic_tools_interfaces::srv::MuxDelete>::SharedPtr mux_delete_srv_;
Expand Down
7 changes: 4 additions & 3 deletions topic_tools/src/demux_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,13 +30,14 @@ DemuxNode::DemuxNode(const rclcpp::NodeOptions & options)
using std::placeholders::_1;
using std::placeholders::_2;

output_topic_ = declare_parameter("initial_topic", "");
initial_topic_ = declare_parameter("initial_topic", "");
input_topic_ = declare_parameter("input_topic", "~/input");
lazy_ = false;
output_topics_ = declare_parameter<std::vector<std::string>>("output_topics");
if (output_topic_.empty()) {
output_topic_ = output_topics_.front();
if (initial_topic_.empty()) {
initial_topic_ = output_topics_.front();
}
output_topic_ = initial_topic_;

discovery_timer_ = this->create_wall_timer(
discovery_period_, std::bind(&DemuxNode::make_subscribe_unsubscribe_decisions, this));
Expand Down
7 changes: 4 additions & 3 deletions topic_tools/src/mux_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,13 +29,14 @@ MuxNode::MuxNode(const rclcpp::NodeOptions & options)
using std::placeholders::_1;
using std::placeholders::_2;

input_topic_ = declare_parameter("initial_topic", "");
initial_topic_ = declare_parameter("initial_topic", "");
output_topic_ = declare_parameter("output_topic", "~/selected");
lazy_ = declare_parameter<bool>("lazy", false);
input_topics_ = declare_parameter<std::vector<std::string>>("input_topics");
if (input_topic_.empty()) {
input_topic_ = input_topics_.front();
if (initial_topic_.empty()) {
initial_topic_ = input_topics_.front();
}
input_topic_ = initial_topic_;

discovery_timer_ = this->create_wall_timer(
discovery_period_,
Expand Down

0 comments on commit 867567e

Please sign in to comment.