1 from nav_msgs.msg
import Odometry
2 from sensor_msgs.msg
import Imu, MagneticField, NavSatFix
3 from microstrain_inertial_msgs.msg
import GNSSAidingStatus, GNSSFixInfo, GNSSDualAntennaStatus, FilterStatus, RTKStatusV1, RTKStatus, FilterAidingMeasurementSummary
5 from .constants
import _DEFAULT_VAL, _DEFAULT_STR
6 from .constants
import _UNIT_DEGREES, _UNIT_GS, _UNIT_GUASSIAN, _UNIT_METERS, _UNIT_RADIANS, _UNIT_METERS_PER_SEC, _UNIT_RADIANS_PER_SEC
7 from .constants
import _ICON_GREY_UNCHECKED_MEDIUM, _ICON_YELLOW_UNCHECKED_MEDIUM, _ICON_YELLOW_CHECKED_MEDIUM, _ICON_GREEN_UNCHECKED_MEDIUM,_ICON_GREEN_CHECKED_MEDIUM, _ICON_TEAL_UNCHECKED_MEDIUM, _ICON_TEAL_CHECKED_MEDIUM, _ICON_BLUE_UNCHECKED_MEDIUM, _ICON_BLUE_CHECKED_MEDIUM, _ICON_RED_UNCHECKED_MEDIUM, _ICON_RED_CHECKED_MEDIUM
8 from .common
import SubscriberMonitor
13 def __init__(self, node, node_name, topic_name):
14 super(GNSSAidingStatusMonitor, self).
__init__(node, node_name, topic_name, GNSSAidingStatus)
51 def __init__(self, node, node_name, topic_name):
52 super(GNSSFixInfoMonitor, self).
__init__(node, node_name, topic_name, GNSSFixInfo)
65 if fix_type
is not _DEFAULT_VAL:
66 if fix_type == GNSSFixInfo.FIX_3D:
67 return "3D Fix (%d)" % fix_type
68 elif fix_type == GNSSFixInfo.FIX_2D:
69 return "2D Fix (%d)" % fix_type
70 elif fix_type == GNSSFixInfo.FIX_TIME_ONLY:
71 return "Time Only (%d)" % fix_type
72 elif fix_type == GNSSFixInfo.FIX_NONE:
73 return "None (%d)" % fix_type
74 elif fix_type == GNSSFixInfo.FIX_INVALID:
75 return "Invalid Fix (%d)" % fix_type
76 elif fix_type == GNSSFixInfo.FIX_RTK_FLOAT:
77 return "RTK Float (%d)" % fix_type
78 elif fix_type == GNSSFixInfo.FIX_RTK_FIXED:
79 return "RTK Fixed (%d)" % fix_type
81 return "Invalid (%d)" % fix_type
91 def __init__(self, node, node_name, topic_name, device_report_monitor):
92 super(FilterStatusMonitor, self).
__init__(node, node_name, topic_name, FilterStatus)
108 if filter_state
is not _DEFAULT_VAL:
111 if filter_state == 1:
112 return "GQ7 Init (%d)" % filter_state
113 elif filter_state == 2:
114 return "GQ7 Vertical Gyro (%d)" % filter_state
115 elif filter_state == 3:
116 return "GQ7 AHRS (%d)" % filter_state
117 elif filter_state == 4:
118 return "GQ7 Full Nav (%d)" % filter_state
120 return "GQ7 Invalid (%d)" % filter_state
122 if filter_state == 0:
123 return "GX5 Startup (%d)" % filter_state
124 elif filter_state == 1:
125 return "GX5 Initialization (%d)" % filter_state
126 elif filter_state == 2:
127 return "GX5 Running, Solution Valid (%d)" % filter_state
128 elif filter_state == 3:
129 return "GX5 Running, Solution Error (%d)" % filter_state
131 return "Unknown Device (%d)" % filter_state
138 if filter_state_string
is not _DEFAULT_STR:
140 return filter_state_string[4:-4]
142 return filter_state_string
147 if status_flags
is not _DEFAULT_VAL:
151 if status_flags & 0b11 == 1:
152 status_str +=
"Stable," 153 elif status_flags & 0b11 == 2:
154 status_str +=
"Converging," 155 elif status_flags & 0b11 == 3:
156 status_str +=
"Unstable/Recovering," 159 if status_flags & 0b100 != 0:
160 status_str +=
"Roll/Pitch Warning," 161 if status_flags & 0b1000 != 0:
162 status_str +=
"Heading Warning," 163 if status_flags & 0b10000 != 0:
164 status_str +=
"Position Warning," 165 if status_flags & 0b100000 != 0:
166 status_str +=
"Velocity Warning," 167 if status_flags & 0b1000000 != 0:
168 status_str +=
"IMU Bias Warning," 169 if status_flags & 0b10000000 != 0:
170 status_str +=
"GNSS Clock Warning," 171 if status_flags & 0b100000000 != 0:
172 status_str +=
"Antenna Lever Arm Warning," 173 if status_flags & 0b1000000000 != 0:
174 status_str +=
"Mounting Transform Warning," 177 if status_flags & 0b1111000000000000 != 0:
178 status_str +=
"Solution Error," 182 if filter_state
is not _DEFAULT_VAL:
184 if filter_state == 1:
185 if status_flags & 0b1000000000000 != 0:
186 status_str +=
"Attutude not initialized," 187 if status_flags & 0b10000000000000 != 0:
188 status_str +=
"Position & Velocity not initialized," 191 elif filter_state
in (2, 3):
192 if status_flags & 0b1 != 0:
193 status_str +=
"IMU unavailable," 194 if status_flags & 0b10 != 0:
195 status_str +=
"GNSS," 196 if status_flags & 0b1000 != 0:
197 status_str +=
"Matrix Singularity in calculation," 198 if status_flags & 0b10000 != 0:
199 status_str +=
"Position covariance high warning," 200 if status_flags & 0b100000 != 0:
201 status_str +=
"Velocity covariance high warning," 202 if status_flags & 0b1000000 != 0:
203 status_str +=
"Attitude covariance high warning," 204 if status_flags & 0b10000000 != 0:
205 status_str +=
"NAN in solution," 206 if status_flags & 0b100000000 != 0:
207 status_str +=
"Gyro bias estimate high warning," 208 if status_flags & 0b1000000000 != 0:
209 status_str +=
"Accel bias estimate high warning," 210 if status_flags & 0b10000000000 != 0:
211 status_str +=
"Gyro scale factor estimate high warning," 212 if status_flags & 0b100000000000 != 0:
213 status_str +=
"Accel scale factor estimate high warning," 214 if status_flags & 0b1000000000000 != 0:
215 status_str +=
"Mag bias estimate high warning," 216 if status_flags & 0b10000000000000 != 0:
217 status_str +=
"GNSS antenna offset correction estimate high warning," 218 if status_flags & 0b100000000000000 != 0:
219 status_str +=
"Hard Iron offset estimate high warning," 220 if status_flags & 0b1000000000000000 != 0:
221 status_str +=
"Soft iron correction estimate high warning," 229 status_str =
"Unknown Filter State," 231 status_str =
"Uknown Device," 235 return "%s (%d)" % (status_str[:-1], status_flags)
237 return "Unknown Status Flags (%d)" % status_flags
244 _MIN_COVARIANCE_SIZE = 36
246 def __init__(self, node, node_name, topic_name, llh=True):
247 super(OdomMonitor, self).
__init__(node, node_name, topic_name, Odometry, callback=self.
_callback)
440 super(GNSSDualAntennaStatusMonitor, self).
__init__(node, node_name, topic_name, GNSSDualAntennaStatus)
469 if fix_type
is not _DEFAULT_VAL:
471 return "None (%d)" % fix_type
473 return "Float (%d)" % fix_type
475 return "Fixed (%d)" % fix_type
505 super(ImuMonitor, self).
__init__(node, node_name, topic_name, Imu)
559 super(MagMonitor, self).
__init__(node, node_name, topic_name, MagneticField)
588 _MIN_COVARIANCE_SIZE = 9
591 super(NavSatFixMonitor, self).
__init__(node, node_name, topic_name, NavSatFix)
607 def __init__(self, node, node_name, topic_name, message_type):
608 super(RTKMonitorBase, self).
__init__(node, node_name, topic_name, message_type)
613 if epoch_status
is not _DEFAULT_VAL:
614 return epoch_status & 0b100 != 0
621 if epoch_status
is not _DEFAULT_VAL:
622 return epoch_status & 0b1000 != 0
629 if epoch_status
is not _DEFAULT_VAL:
630 return epoch_status & 0b10000 != 0
637 if epoch_status
is not _DEFAULT_VAL:
638 return epoch_status & 0b100000 != 0
687 class RTKMonitor(RTKMonitorBase):
690 super(RTKMonitor, self).
__init__(node, node_name, topic_name, RTKStatus)
703 if rssi
is not _DEFAULT_VAL:
710 tower_change_indicator = self.
_current_message.dongle_tower_change_indicator
711 if tower_change_indicator
is not _DEFAULT_VAL:
712 return tower_change_indicator
719 if nmea_timeout
is not _DEFAULT_VAL:
727 if server_timeout
is not _DEFAULT_VAL:
728 return server_timeout
735 if rtcm_timeout
is not _DEFAULT_VAL:
743 if out_of_range
is not _DEFAULT_VAL:
750 corrections_unavailable = self.
_current_message.dongle_corrections_unavailable
751 if corrections_unavailable
is not _DEFAULT_VAL:
752 return corrections_unavailable
759 if modem_state
is not _DEFAULT_VAL:
761 return "Off (%d)" % modem_state
763 return "No Network (%d)" % modem_state
765 return "Connected (%d)" % modem_state
766 elif modem_state == self.
_current_message.MODEM_STATE_CONFIGURING_DATA_CONTEXT:
767 return "Configuring Data Context (%d)" % modem_state
768 elif modem_state == self.
_current_message.MODEM_STATE_ACTIVATING_DATA_CONTEXT:
769 return "Activating Data Context (%d)" % modem_state
771 return "Configuring Socket (%d)" % modem_state
772 elif modem_state == self.
_current_message.MODEM_STATE_WAITING_ON_SERVER_HANDSHAKE:
773 return "Waiting on Server Handshake (%d)" % modem_state
775 return "Connected & Idle (%d)" % modem_state
776 elif modem_state == self.
_current_message.MODEM_STATE_CONNECTED_AND_STREAMING:
777 return "Connected & Streaming (%d)" % modem_state
779 return "Invalid (%d)" % modem_state
786 if connection_type
is not _DEFAULT_VAL:
788 return "No Connection (%d)" % connection_type
789 elif connection_type == self.
_current_message.CONNECTION_TYPE_CONNECTION_2G:
790 return "2G (%d)" % connection_type
791 elif connection_type == self.
_current_message.CONNECTION_TYPE_CONNECTION_3G:
792 return "3G (%d)" % connection_type
793 elif connection_type == self.
_current_message.CONNECTION_TYPE_CONNECTION_4G:
794 return "4G (%d)" % connection_type
795 elif connection_type == self.
_current_message.CONNECTION_TYPE_CONNECTION_5G:
796 return "5G (%d)" % connection_type
798 return "Invalid (%d)" % connection_type
833 if modem_state
is not _DEFAULT_VAL:
835 return _ICON_YELLOW_UNCHECKED_MEDIUM
837 return _ICON_GREEN_CHECKED_MEDIUM
838 elif modem_state == self.
_current_message.MODEM_STATE_CONFIGURING_DATA_CONTEXT:
839 return _ICON_GREEN_CHECKED_MEDIUM
840 elif modem_state == self.
_current_message.MODEM_STATE_ACTIVATING_DATA_CONTEXT:
841 return _ICON_GREEN_CHECKED_MEDIUM
843 return _ICON_GREEN_CHECKED_MEDIUM
844 elif modem_state == self.
_current_message.MODEM_STATE_WAITING_ON_SERVER_HANDSHAKE:
845 return _ICON_GREEN_CHECKED_MEDIUM
847 return _ICON_BLUE_CHECKED_MEDIUM
848 elif modem_state == self.
_current_message.MODEM_STATE_CONNECTED_AND_STREAMING:
849 return _ICON_BLUE_CHECKED_MEDIUM
851 return _ICON_GREY_UNCHECKED_MEDIUM
857 super(RTKMonitorV1, self).
__init__(node, node_name, topic_name, RTKStatusV1)
882 if controller_state
is not _DEFAULT_VAL:
883 if controller_state == 0:
884 return "Idle (%d)" % controller_state
885 elif controller_state == 4:
886 return "Active (%d)" % controller_state
888 return "Invalid (%d)" % controller_state
895 if controller_status
is not _DEFAULT_VAL:
896 if controller_status == 0:
897 return "Controller OK (%d)" % controller_status
898 elif controller_status == 1:
899 return "Awaiting NMEA (%d)" % controller_status
900 elif controller_status == 2:
901 return "RTK Timed Out (%d)" % controller_status
902 elif controller_status == 3:
903 return "RTK Unavailable (%d)" % controller_status
904 elif controller_status == 7:
905 return "Invalid Configuration (%d)" % controller_status
907 return "Invalid (%d)" % controller_status
914 if platform_state
is not _DEFAULT_VAL:
915 if platform_state == 0:
916 return "Modem Powered Down (%d)" % platform_state
917 elif platform_state == 1:
918 return "Modem Powering Up (%d)" % platform_state
919 elif platform_state == 2:
920 return "Configuring Modem (%d)" % platform_state
921 elif platform_state == 3:
922 return "Modem Powering Down (%d)" % platform_state
923 elif platform_state == 4:
924 return "Modem Ready (%d)" % platform_state
925 elif platform_state == 5:
926 return "Connecting to Network (%d)" % platform_state
927 elif platform_state == 6:
928 return "Disconnecting from Network (%d)" % platform_state
929 elif platform_state == 7:
930 return "Connected to Network (%d)" % platform_state
931 elif platform_state == 8:
932 return "Connecting to RTK Service (%d)" % platform_state
933 elif platform_state == 9
or platform_state == 10:
934 return "Unable to Connect to RTK Service (%d)" % platform_state
935 elif platform_state == 11:
936 return "Disconnecting From RTK Service (%d)" % platform_state
937 elif platform_state == 12:
938 return "Connected to RTK Service (%d)" % platform_state
939 elif platform_state == 13
or platform_state == 14:
940 return "Device Error (%d)" 942 return "Invalid (%d)" % platform_state
949 if platform_status
is not _DEFAULT_VAL:
950 if platform_status == 0:
951 return "Platform OK (%d)" % platform_status
952 elif platform_status == 4:
953 return "RTK Service Connection Broken (%d)" % platform_status
954 elif platform_status == 6:
955 return "Cell Connection Dropped (%d)" % platform_status
956 elif platform_status == 7:
957 return "Modem Error (%d)" % platform_status
959 return "Invalid (%d)" % platform_status
966 if reset_reason
is not _DEFAULT_VAL:
967 if reset_reason == 0:
968 return "Power On (%d)" % reset_reason
969 elif reset_reason == 1:
970 return "Unknown (%d)" % reset_reason
971 elif reset_reason == 2:
972 return "Software Reset (%d)" % reset_reason
973 elif reset_reason == 3:
974 return "Hardware Error Reset (%d)" % reset_reason
976 return "Invalid (%d)" 983 if platform_state
is not _DEFAULT_VAL:
984 if platform_state == 0:
985 return _ICON_GREY_UNCHECKED_MEDIUM
986 elif platform_state
in (1, 2, 4, 5):
987 return _ICON_GREEN_UNCHECKED_MEDIUM
988 elif platform_state
in (3, 6):
989 return _ICON_GREEN_CHECKED_MEDIUM
990 elif platform_state
in (7, 8, 11, 12):
993 if low_signal_quality:
994 return _ICON_TEAL_CHECKED_MEDIUM
if out_of_range
else _ICON_TEAL_UNCHECKED_MEDIUM
996 return _ICON_BLUE_CHECKED_MEDIUM
if out_of_range
else _ICON_BLUE_UNCHECKED_MEDIUM
997 elif platform_state
in (9, 10):
998 return _ICON_RED_UNCHECKED_MEDIUM
999 elif platform_state
in (13, 14):
1000 return _ICON_RED_CHECKED_MEDIUM
1002 return _ICON_GREY_UNCHECKED_MEDIUM
1004 return _ICON_GREY_UNCHECKED_MEDIUM
1010 super(FilterAidingMeasurementSummaryMonitor, self).
__init__(node, node_name, topic_name, FilterAidingMeasurementSummary)
1126 def __init__(self, filter_status_monitor, gnss_1_aiding_status_monitor, gnss_2_aiding_status_monitor):
1135 if filter_state
is not _DEFAULT_VAL:
1136 if filter_state == 1:
1137 return _ICON_YELLOW_CHECKED_MEDIUM
1138 elif filter_state == 2
or filter_state == 3:
1139 return _ICON_YELLOW_UNCHECKED_MEDIUM
1140 elif filter_state == 4:
1143 if (gnss_1_differential
is not _DEFAULT_VAL
and gnss_1_differential)
or (gnss_2_differential
is not _DEFAULT_VAL
and gnss_2_differential):
1144 return _ICON_BLUE_CHECKED_MEDIUM
1146 return _ICON_GREEN_CHECKED_MEDIUM
1148 return _ICON_GREY_UNCHECKED_MEDIUM
def status_flags_string(self)
def gnss1_enabled_string(self)
def __init__(self, node, node_name, topic_name, device_report_monitor)
def _callback(self, status_message)
def position_z_string(self)
def magnetometer_used(self)
def dual_antenna_enabled(self)
def orientation_x_string(self)
def orientation_y_string(self)
def beidou_received(self)
def differential_corrections(self)
def orientation_uncertainty_z(self)
def tower_change_indicator_string(self)
def heading_uncertainty(self)
def position_uncertainty_y(self)
def glonass_received(self)
def __init__(self, filter_status_monitor, gnss_1_aiding_status_monitor, gnss_2_aiding_status_monitor)
def __init__(self, node, node_name, topic_name)
def filter_state_led_string(self)
def magnetometer_enabled_string(self)
def magnetometer_used_string(self)
def position_uncertainty_x(self)
def position_uncertainty_z(self)
def _get_string_units(self, val, units, default_val=_DEFAULT_VAL, default_str=_DEFAULT_STR)
def rec_2_data_valid_string(self)
def position_y_string(self)
def corrections_unavailable(self)
def fix_type_string(self)
def velocity_y_string(self)
def heading_used_string(self)
def gnss2_enabled_string(self)
def controller_state(self)
def pressure_enabled_string(self)
def __init__(self, node, node_name, topic_name, llh=True)
def velocity_uncertainty_z_string(self)
def __init__(self, node, node_name, topic_name)
def __init__(self, node, node_name, topic_name)
def rec_1_data_valid_string(self)
def orientation_uncertainty_y_string(self)
def antenna_offsets_valid(self)
def _get_string(self, val, default_val=_DEFAULT_VAL, default_str=_DEFAULT_STR)
def orientation_uncertainty_x(self)
def velocity_uncertainty_x_string(self)
def server_timeout_string(self)
def velocity_uncertainty_z(self)
def dual_antenna_used_string(self)
def differential_corrections_string(self)
def controller_state_string(self)
def signal_quality_string(self)
def position_x_string(self)
def connection_type(self)
def fix_type_string(self)
def corrections_unavailable_string(self)
def connection_type_string(self)
def _get_boolean_string(self, val, default_val=_DEFAULT_VAL)
def velocity_uncertainty_y(self)
_gnss_1_aiding_status_monitor
def orientation_uncertainty_x_string(self)
def heading_enabled_string(self)
def dual_antenna_used(self)
def _get_string_hex(self, val, default_val=_DEFAULT_VAL, default_str=_DEFAULT_STR)
def gnss1_used_string(self)
def speed_enabled_string(self)
def velocity_x_string(self)
def velocity_z_string(self)
def _default_callback(self, message)
def platform_state_string(self)
def gnss2_used_string(self)
def raw_status_flags_string(self)
def filter_state_string(self)
def position_uncertainty(self)
def position_uncertainty_x_string(self)
def tower_change_indicator(self)
def __init__(self, node, node_name, topic_name)
def out_of_range_string(self)
def velocity_uncertainty_y_string(self)
def heading_enabled(self)
def integer_fix_string(self)
def platform_status(self)
def pressure_enabled(self)
def galileo_received_string(self)
def position_uncertainty_y_string(self)
def reset_reason_string(self)
def rec_2_data_valid(self)
def __init__(self, node, node_name, topic_name)
def glonass_received_string(self)
def __init__(self, node, node_name, topic_name)
_gnss_2_aiding_status_monitor
def __init__(self, node, node_name, topic_name)
def dual_antenna_enabled_string(self)
def __init__(self, node, node_name, topic_name)
def gps_received_string(self)
def antenna_offsets_valid_string(self)
def nmea_timeout_string(self)
def __init__(self, node, node_name, topic_name)
def orientation_z_string(self)
def raw_status_flags(self)
def orientation_uncertainty_y(self)
def rtcm_timeout_string(self)
def __init__(self, node, node_name, topic_name, message_type)
def _get_val(self, val, default=_DEFAULT_VAL)
def rec_1_data_valid(self)
def _euler_from_quaternion(self, quaternion)
def controller_status_string(self)
def orientation_uncertainty_z_string(self)
def pressure_used_string(self)
def galileo_received(self)
def tight_coupling_string(self)
def platform_status_string(self)
def position_uncertainty_string(self)
def _get_small_boolean_icon_string(self, val, default_val=_DEFAULT_VAL)
def speed_used_string(self)
def heading_uncertainty_string(self)
def position_fix_string(self)
def position_uncertainty_z_string(self)
def velocity_uncertainty_x(self)
def beidou_received_string(self)
def modem_state_string(self)
def magnetometer_enabled(self)