ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
You always get self.connections == 0 because you don't update the value within your while loop. But this is not the main issue with your code.
How I understand you question is that you want to have a node that subscribes to a topic and stores the current heading if a service is triggered and afterwards provides this selected heading to all nodes that subscribe to a second topic. In this case, your code could look like this:
A latched publisher automatically sends its current message to any new subscriber.
class save_hdg(object):
def __init__(self):
self.latch_publisher = rospy.Publisher('/autonomous/saved_heading',
Float64, queue_size=10, latch=True) # TURNING ON LATCHING
self.serv = rospy.Service('/autonomous/save_heading', Empty, self.publish_once_only)
self.hdg_subscriber = rospy.Subscriber('/mavros/global_position/compass_hdg', Float64,
self.subscriber_callback, queue_size=1)
# initialize all member variables in init
self.heading_received = False
self.current_heading = self.hdg = None
rospy.loginfo("The save heading service is ready")
def publish_once_only(self, req):
rospy.loginfo("save heading service has been called")
if self.heading_received:
self.hdg = self.current_heading
self.latch_publisher.publish(self.hdg)
else:
rospy.logwarn("Did not receive heading yet, can't republish")
return EmptyResponse()
def subscriber_callback(self, msg):
self.heading_received = True
self.current_heading = msg.data
if __name__ == "__main__":
rospy.init_node("save_heading_ServiceServer")
save_heading_object = save_hdg()
rospy.spin()