@@ -103,11 +103,11 @@ async def main():
103
103
ctd_publisher = rospy .Publisher ('~' , Ctd , queue_size = 5 )
104
104
if has_depth :
105
105
depth_publisher = rospy .Publisher ('~depth' , DepthPressure , queue_size = 5 )
106
- channel_publishers = [
107
- rospy . Publisher ( f'~ { ros_safe ( c ) } ' , RbrMeasurement , queue_size = 5 )
108
- for c , u in channels
109
- ]
110
-
106
+ channel_publishers = []
107
+ for c , u in channels :
108
+ if c == 'depth' :
109
+ continue
110
+ channel_publishers . append ( rospy . Publisher ( f'~ { ros_safe ( c ) } ' , RbrMeasurement , queue_size = 5 ))
111
111
112
112
# Subscribe to incoming comms messages
113
113
handler = lambda msg : asyncio .run_coroutine_threadsafe (ros_msg_q .put (msg ),
@@ -143,9 +143,9 @@ async def main():
143
143
144
144
# Construct the Ctd message
145
145
ctd = Ctd ()
146
- ctd .conductivity = c .get ('conductivity' , math .nan )
147
- ctd .temperature = c .get ('temperature' , math .nan )
148
- ctd .pressure = c .get ('pressure' , math .nan )
146
+ ctd .conductivity = values .get ('conductivity' , math .nan )
147
+ ctd .temperature = values .get ('temperature' , math .nan )
148
+ ctd .pressure = values .get ('pressure' , math .nan )
149
149
150
150
# Clear fields with no measurement
151
151
ctd .salinity = math .nan
@@ -158,13 +158,12 @@ async def main():
158
158
159
159
# Construct the DepthPressure message
160
160
dp = DepthPressure ()
161
- dp .depth = c .get ('depth' , math .nan )
161
+ dp .depth = values .get ('depth' , math .nan )
162
162
dp .latitude = DepthPressure .DEPTH_PRESSURE_NO_DATA
163
163
dp .tare = DepthPressure .DEPTH_PRESSURE_NO_DATA
164
- dp .pressure_raw = c .get ('pressure' , math .nan )
164
+ dp .pressure_raw = values .get ('pressure' , math .nan )
165
165
dp .pressure_raw_unit = DepthPressure .UNIT_PRESSURE_DBAR
166
- dp .pressure = c .get ('pressure' , math .nan )
167
-
166
+ dp .pressure = values .get ('pressure' , math .nan )
168
167
169
168
# Construct the RbrMeasurement messages
170
169
rbr_msgs = []
0 commit comments