Skip to content

Commit

Permalink
Fixed PR comments
Browse files Browse the repository at this point in the history
  • Loading branch information
alexoj46 committed Oct 26, 2024
1 parent 9e687b8 commit 66f3b93
Show file tree
Hide file tree
Showing 3 changed files with 21 additions and 18 deletions.
2 changes: 1 addition & 1 deletion mil_common/drivers/mil_passive_sonar/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,4 +37,4 @@ add_executable(sylphase_sonar_ros_bridge src/sylphase_ros_bridge.cpp)
target_link_libraries(sylphase_sonar_ros_bridge ${catkin_LIBRARIES})
add_dependencies(sylphase_sonar_ros_bridge ${catkin_EXPORTED_TARGETS})

install(PROGRAMS scripts/ping_publisher.py scripts/ping_printer scripts/ping_logger scripts/ping_plotter scripts/hydrophones DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
install(PROGRAMS scripts/ping_publisher scripts/ping_printer scripts/ping_logger scripts/ping_plotter scripts/hydrophones DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
35 changes: 19 additions & 16 deletions mil_common/drivers/mil_passive_sonar/scripts/ping_publisher.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,32 +13,35 @@
def main():
# Define the server address and port
HOST = "127.0.0.1"
PORT = 2007 # The port used by the server
PORT = 2007

# Create a socket
with socket.socket(socket.AF_INET, socket.SOCK_STREAM) as s:
pub = rospy.Publisher("hydrophones/solved", ProcessedPing, queue_size=10)
s.connect((HOST, PORT))
print(f"Connected to {HOST}:{PORT}")
pub = rospy.Publisher("ping", ProcessedPing, queue_size=10)
rospy.init_node("pingpublisher", anonymous=True)
rospy.loginfo(
f"\nConnected to {HOST}:{PORT}\nPublishing to /hydrophones/solved",
)

# Need to ignore the first 2 JSON Parse Errors (nothing wrong)
parse_error_count = 0

while not rospy.is_shutdown():
# Receive data
data = s.recv(1024) # Buffer size is 1024 bytes
data = s.recv(1024)
if not data:
break

# Parse the JSON data
try:
json_data = json.loads(data.decode("utf-8"))
# Create a ProcessedPing message
ping_msg = ProcessedPing()

# Populate the header
ping_msg.header = Header()
ping_msg.header.seq += 1 # Increment sequence number
ping_msg.header.seq += 1
ping_msg.header.stamp = rospy.Time.now()
ping_msg.header.frame_id = "ping_frame" # Set your frame_id
ping_msg.header.frame_id = "hydrophones"

# Populate the position
ping_msg.position = Point()
Expand All @@ -48,21 +51,21 @@ def main():

# Populate the frequency and amplitude
ping_msg.freq = json_data["frequency_Hz"]
ping_msg.amplitude = json_data[
"origin_distance_m"
] # You can modify this as needed
ping_msg.valid = True # Or set to False based on your logic
ping_msg.amplitude = json_data["origin_distance_m"]
ping_msg.valid = True

# Publish the message
pub.publish(ping_msg)
rospy.loginfo(f"Published: {ping_msg}")

except json.JSONDecodeError as e:
rospy.loginfo(f"JSON Decode Error: {e}")
parse_error_count += 1
# ignore first two (normal behavior)
if parse_error_count > 2:
rospy.logerr(f"JSONDecodeError: {e}")
except KeyError as e:
rospy.loginfo(f"Key Error: {e}")
rospy.logerr(f"Key Error: {e}")


if __name__ == "__main__":
with contextlib.suppress(rospy.ROSInterruptException):
rospy.init_node("pingpublisher", anonymous=True)
main()
2 changes: 1 addition & 1 deletion mil_common/drivers/mil_passive_sonar/src/pipeline.sh
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
#!/bin/bash

sdgps connect-sonar-raw-tcp --host 192.168.37.51 --port 2006 ! filter-sonar-raw-samples --highpass 15e3 --lowpass 45e3 --notch 40e3 ! extract-robosub-pings ! robosub-ping-solver ! listen-robosub-ping-solution-tcp 2007
sdgps connect-sonar-raw-tcp --host 192.168.37.61 --port 2006 ! filter-sonar-raw-samples --highpass 15e3 --lowpass 45e3 --notch 40e3 ! extract-robosub-pings ! robosub-ping-solver ! listen-robosub-ping-solution-tcp 2007

0 comments on commit 66f3b93

Please sign in to comment.