ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | Q&A answers.ros.org |
![]() | 1 | initial version |
If you subscribe to a new topic using the same callback and store the result in the same Subscriber object, storing that new value in the original variable should unsubscribe the other topic.
![]() | 2 | provide example |
If you subscribe to a new topic using the same callback and store the result in the same Subscriber object, storing that new value in the original variable should unsubscribe the other topic.
EXAMPLE: untested, probably buggy
class Reader
{
public:
Reader(ros::NodeHandle node)
{
node_ = node;
// subscribe to original topic
topic_ = node.subscribe("first_topic", 10,
&Reader::callback, (Reader *) this);
}
private:
void callback(const std_msgs::String::ConstPtr &msg)
{
if (msg->data == "switch")
{
// subscribe to other topic
topic_ = node_.subscribe("next_topic", 10,
&Reader::callback, (Reader *) this);
}
else
{
// log message from current topic
ROS_INFO_STREAM(msg->data);
}
}
// class variables
ros::NodeHandle node_;
ros::Subscriber topic_; // current topic subscription
};
int main(int argc, char **argv)
{
ros::init(argc, argv, "your_node");
ros::NodeHandle node;
Reader read(node);
ros::spin();
return 0;
}