Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

navigator_battery_monitor package migrated to ros2 #1167

Merged
merged 2 commits into from
Mar 30, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,10 @@
"""


import sys

import message_filters
import rospy
import rclpy
from roboteq_msgs.msg import Feedback, Status
from ros_alarms import AlarmListener
from ros_alarms_msgs.msg import Alarm
Expand Down Expand Up @@ -49,7 +51,7 @@ def __init__(self):
self._hw_kill_listener.wait_for_server()

# The publisher for the averaged voltage
self.pub_voltage = rospy.Publisher("/battery_monitor", Float32, queue_size=1)
self.pub_voltage = node.create_publisher(Float32, "/battery_monitor", 1)

# Subscribes to the feedback from each of the four thrusters
motor_topics = ["/FL_motor", "/FR_motor", "/BL_motor", "/BR_motor"]
Expand Down Expand Up @@ -117,7 +119,8 @@ def publish_voltage(self, _) -> None:


if __name__ == "__main__":
rospy.init_node("battery_monitor")
rclpy.init(args=sys.argv)
node = rclpy.create_node("battery_monitor")
monitor = BatteryMonitor()
rospy.Timer(rospy.Duration(1), monitor.publish_voltage, oneshot=False)
rospy.spin()
node.create_timer(1.0, monitor.publish_voltage)
rclpy.spin()
Loading