-
Notifications
You must be signed in to change notification settings - Fork 29
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
python publisher for sdgps solution to hydrophone pings
- Loading branch information
Showing
4 changed files
with
75 additions
and
1 deletion.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
68 changes: 68 additions & 0 deletions
68
mil_common/drivers/mil_passive_sonar/scripts/ping_publisher.py
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,68 @@ | ||
#!/usr/bin/env python3 | ||
|
||
import contextlib | ||
import json | ||
import socket | ||
|
||
import rospy | ||
from geometry_msgs.msg import Point | ||
from mil_passive_sonar.msg import ProcessedPing | ||
from std_msgs.msg import Header | ||
|
||
|
||
def main(): | ||
# Define the server address and port | ||
HOST = "127.0.0.1" | ||
PORT = 2007 # The port used by the server | ||
|
||
# Create a socket | ||
with socket.socket(socket.AF_INET, socket.SOCK_STREAM) as s: | ||
s.connect((HOST, PORT)) | ||
print(f"Connected to {HOST}:{PORT}") | ||
pub = rospy.Publisher("ping", ProcessedPing, queue_size=10) | ||
rospy.init_node("pingpublisher", anonymous=True) | ||
|
||
while not rospy.is_shutdown(): | ||
# Receive data | ||
data = s.recv(1024) # Buffer size is 1024 bytes | ||
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.stamp = rospy.Time.now() | ||
ping_msg.header.frame_id = "ping_frame" # Set your frame_id | ||
|
||
# Populate the position | ||
ping_msg.position = Point() | ||
ping_msg.position.x = json_data["origin_direction_body"][0] | ||
ping_msg.position.y = json_data["origin_direction_body"][1] | ||
ping_msg.position.z = json_data["origin_direction_body"][2] | ||
|
||
# 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 | ||
|
||
# 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}") | ||
except KeyError as e: | ||
rospy.loginfo(f"Key Error: {e}") | ||
|
||
|
||
if __name__ == "__main__": | ||
with contextlib.suppress(rospy.ROSInterruptException): | ||
main() |
3 changes: 3 additions & 0 deletions
3
mil_common/drivers/mil_passive_sonar/src/fakeping_pipeline.sh
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,3 @@ | ||
#!/bin/bash | ||
|
||
sdgps generate-fake-sonar-solution --rate 1 --position '[-30, 10, -2]' --circle '{"radius":3,"axis":[0,0,1],"period":30}' ! sonar-simulate --role rover --transmit-pattern robosub-2019 --base-hydrophone-arrangement robosub-2019 --rover-hydrophone-arrangement uf-mil-sub7 --cn0 80 --multipath extreme ! filter-sonar-raw-samples --highpass 15e3 --lowpass 45e3 --notch 40e3 ! extract-robosub-pings ! robosub-ping-solver ! listen-robosub-ping-solution-tcp 2007 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +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 |