Skip to content

Commit

Permalink
tested and added low_battery boolean parameter to prevent repeating p…
Browse files Browse the repository at this point in the history
…op ups
  • Loading branch information
tcappellari-bdai committed Feb 1, 2024
1 parent a756449 commit 64f00a4
Show file tree
Hide file tree
Showing 2 changed files with 14 additions and 5 deletions.
15 changes: 11 additions & 4 deletions spot_driver/spot_driver/ros_helpers.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
from google.protobuf.timestamp_pb2 import Timestamp
from nav_msgs.msg import Odometry
from rclpy.node import Node
from rclpy.parameter import Parameter
from sensor_msgs.msg import CameraInfo, CompressedImage, Image, JointState
from tf2_msgs.msg import TFMessage
from tkinter import messagebox
Expand Down Expand Up @@ -531,7 +532,7 @@ def get_tf_from_world_objects(
return tf_msg


def get_battery_states_from_state(state: robot_state_pb2.RobotState, spot_wrapper: SpotWrapper) -> BatteryStateArray:
def get_battery_states_from_state(state: robot_state_pb2.RobotState, spot_wrapper: SpotWrapper, node: Node) -> BatteryStateArray:
"""Maps battery state data from robot state proto to ROS BatteryStateArray message
Args:
state: Robot State proto
Expand All @@ -557,12 +558,18 @@ def get_battery_states_from_state(state: robot_state_pb2.RobotState, spot_wrappe
battery_msg.status = battery.status
battery_states_array_msg.battery_states.append(battery_msg)

if battery_msg.charge_percentage <= 0.1:
if battery_msg.charge_percentage <= 10 and not node.get_parameter("low_battery").value:
low_battery_param = Parameter(
'low_battery',
Parameter.Type.BOOL,
True
)
node.set_parameters([low_battery_param])
messagebox.showwarning(
title="Warning: Low Battery {}".format(battery_msg.identifier),
message=(
"Battery is at {}. Approximately {} minutes remaining.\n Please charge your Spot soon."
).format(battery_msg.charge_percentage * 100, battery_msg.estimated_runtime.sec / 60),
"Battery is at {} %. Approximately {} minutes remaining.\n Please charge your Spot soon."
).format(battery_msg.charge_percentage, round(battery_msg.estimated_runtime.sec / 60)),
)

return battery_states_array_msg
Expand Down
4 changes: 3 additions & 1 deletion spot_driver/spot_driver/spot_ros2.py
Original file line number Diff line number Diff line change
Expand Up @@ -284,6 +284,8 @@ def __init__(self, parameter_list: Optional[typing.List[Parameter]] = None, **kw
self.declare_parameter("spot_name", "")
self.declare_parameter("mock_enable", False)

self.declare_parameter("low_battery", False)

# If `mock_enable:=True`, then there are additional parameters. We must set this one separately.
set_node_parameter_from_parameter_list(self, parameter_list, "mock_enable")
if self.get_parameter("mock_enable").value:
Expand Down Expand Up @@ -1040,7 +1042,7 @@ def robot_state_callback(self, results: Any) -> None:
self.wifi_pub.publish(wifi_msg)

# Battery States #
battery_states_array_msg = get_battery_states_from_state(state, self.spot_wrapper)
battery_states_array_msg = get_battery_states_from_state(state, self.spot_wrapper, self)
self.battery_pub.publish(battery_states_array_msg)

# Power State #
Expand Down

0 comments on commit 64f00a4

Please sign in to comment.