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

THRUSTERS: raise alarm on fatal thruster configuration #257

Closed
wants to merge 4 commits into from
Closed
Show file tree
Hide file tree
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
118 changes: 85 additions & 33 deletions drivers/sub8_videoray_m5_thruster/nodes/thruster_driver.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
from std_msgs.msg import Header, Float64
from sub8_msgs.msg import Thrust, ThrusterStatus
from mil_ros_tools import wait_for_param, thread_lock
from sub8_msgs.srv import ThrusterInfo, ThrusterInfoResponse, FailThruster, FailThrusterResponse
from sub8_msgs.srv import ThrusterInfo, ThrusterInfoResponse, FailThruster, FailThrusterResponse, UpdateThrusterLayout, BMatrix
from sub8_thruster_comm import thruster_comm_factory
from ros_alarms import AlarmBroadcaster, AlarmListener
lock = threading.Lock()
Expand Down Expand Up @@ -221,38 +221,6 @@ def check_for_drops(self, *args):
rospy.logwarn("Thruster {} has come back online".format(name))
self.alert_thruster_unloss(name)

def alert_thruster_unloss(self, thruster_name):
if thruster_name in self.failed_thrusters:
self.failed_thrusters.remove(thruster_name)

if len(self.failed_thrusters) == 0:
self.thruster_out_alarm.clear_alarm(parameters={"clear_all"})
else:
severity = 3 if len(self.failed_thrusters) <= rospy.get_param("thruster_loss_limit", 2) else 5
rospy.logerr(self.failed_thrusters)
self.thruster_out_alarm.raise_alarm(
parameters={
'thruster_names': self.failed_thrusters,
},
severity=severity
)

def alert_thruster_loss(self, thruster_name, last_update):
if thruster_name not in self.failed_thrusters:
self.failed_thrusters.append(thruster_name)

# Severity rises to 5 if too many thrusters are out
severity = 3 if len(self.failed_thrusters) <= rospy.get_param("thruster_loss_limit", 2) else 5
rospy.logerr(self.failed_thrusters)
self.thruster_out_alarm.raise_alarm(
problem_description='Thruster {} has failed'.format(thruster_name),
parameters={
'thruster_names': self.failed_thrusters,
'last_update': last_update
},
severity=severity
)

def fail_thruster(self, srv):
self.alert_thruster_loss(srv.thruster_name, None)
return FailThrusterResponse()
Expand Down Expand Up @@ -337,6 +305,90 @@ def stop(self):
if name not in self.failed_thrusters:
self.command_thruster(name, 0.0)

def alert_thruster_unloss(self, thruster_name):
if thruster_name in self.failed_thrusters:
self.failed_thrusters.remove(thruster_name)
if len(self.failed_thrusters) == 0:
self.thruster_out_alarm.clear_alarm(parameters={"clear_all"})
try:
update = rospy.ServiceProxy('update_thruster_layout', UpdateThrusterLayout)
update()
get_b = rospy.ServiceProxy('b_matrix', BMatrix)
b_proxy = get_b()
B = np.asmatrix(b_proxy.B).reshape(6, -1)
if (np.linalg.matrix_rank(B) < 6):
self.thruster_out_alarm.raise_alarm(
parameters={
'thruster_names': self.failed_thrusters,
'issue': "B MATRIX IS SINGULAR",
},
severity=5
)

except rospy.ServiceException, e:
rospy.logerr("Service call failed: %s"%e)
# Severity rises to 5 if too many thrusters are out
severity = 3 if len(self.failed_thrusters) <= rospy.get_param("thruster_loss_limit", 2) else 5
rospy.logerr(self.failed_thrusters)
self.thruster_out_alarm.raise_alarm(
problem_description='Thruster {} has failed'.format(thruster_name),
parameters={
'thruster_names': self.failed_thrusters,
'last_update': last_update
},
severity=severity
)

def alert_thruster_loss(self, thruster_name, last_update):
if thruster_name not in self.failed_thrusters:
self.failed_thrusters.append(thruster_name)
try:
update = rospy.ServiceProxy('update_thruster_layout', UpdateThrusterLayout)
update()
get_b = rospy.ServiceProxy('b_matrix', BMatrix)
b_proxy = get_b()
B = np.asmatrix(b_proxy.B).reshape(6, -1)
if (np.linalg.matrix_rank(B) < 6):
self.thruster_out_alarm.raise_alarm(
parameters={
'thruster_names': self.failed_thrusters,
'issue': "B MATRIX IS SINGULAR",
},
severity=5
)

except rospy.ServiceException, e:
rospy.logerr("Service call failed: %s"%e)
# Severity rises to 5 if too many thrusters are out
severity = 3 if len(self.failed_thrusters) <= rospy.get_param("thruster_loss_limit", 2) else 5
rospy.logerr(self.failed_thrusters)
self.thruster_out_alarm.raise_alarm(
problem_description='Thruster {} has failed'.format(thruster_name),
parameters={
'thruster_names': self.failed_thrusters,
'last_update': last_update
},
severity=severity
)

def alert_bus_voltage(self, voltage):
severity = 3
# Kill if the voltage goes too low
if self.bus_voltage < rospy.get_param("/battery/kill_voltage", 44.0):
severity = 5

self.bus_voltage_alarm.raise_alarm(
problem_description='Bus voltage has fallen to {}'.format(voltage),
parameters={
'bus_voltage': voltage,
},
severity=severity
)

def fail_thruster(self, srv):
self.alert_thruster_loss(srv.thruster_name, None)
return FailThrusterResponse()


if __name__ == '__main__':
PKG = 'sub8_videoray_m5_thruster'
Expand Down
13 changes: 9 additions & 4 deletions gnc/sub8_thruster_mapper/nodes/mapper.py
Original file line number Diff line number Diff line change
Expand Up @@ -63,10 +63,14 @@ def update_layout(self, srv):
self.max_thrusts = np.copy(self.default_max_thrusts)

for thruster_name in self.dropped_thrusters:
thruster_index = self.thruster_name_map.index(thruster_name)
self.min_thrusts[thruster_index] = -self.min_commandable_thrust * 0.5
self.max_thrusts[thruster_index] = self.min_commandable_thrust * 0.5

try:
thruster_index = self.thruster_name_map.index(thruster_name)
self.min_thrusts[thruster_index] = -self.min_commandable_thrust * 0.5
self.max_thrusts[thruster_index] = self.min_commandable_thrust * 0.5
except:
print "Failed"
self.thruster_layout['thrusters'].pop(thruster_name, "None")
self.B = self.generate_B(self.thruster_layout)
rospy.logwarn("Layout updated")
return UpdateThrusterLayoutResponse()

Expand Down Expand Up @@ -123,6 +127,7 @@ def generate_B(self, layout):
)
self.num_thrusters += 1
B.append(wrench_column)

return np.transpose(np.array(B))

def map(self, wrench):
Expand Down