Skip to content

Commit

Permalink
fix sdk get_local_ip bug in set_sta. add vrpn launch file
Browse files Browse the repository at this point in the history
  • Loading branch information
tianb03 committed Apr 29, 2021
1 parent 3252f40 commit c732ff8
Show file tree
Hide file tree
Showing 2 changed files with 35 additions and 5 deletions.
15 changes: 10 additions & 5 deletions rmtt_driver/scripts/set_sta.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,13 +14,18 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import sys
import robomaster
from robomaster import robot
import sys,socket
from robomaster import robot,config

def get_local_ip():
s = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
s.setsockopt(socket.SOL_SOCKET, socket.SO_BROADCAST, 1)
s.connect(('<broadcast>', 0))
return s.getsockname()[0]

if __name__ == '__main__':

config.LOCAL_IP_STR = get_local_ip()
print(config.LOCAL_IP_STR)
tl_drone = robot.Drone()
tl_drone.initialize()
version = tl_drone.get_sdk_version()
Expand All @@ -41,4 +46,4 @@
print("Wifi configured to ssid: {0}, please switch TT to router mode".format(ssid))
tl_drone.close()

sys.exit("Use Ctrl + C to exit")
sys.exit("Press Ctrl + C to exit.")
25 changes: 25 additions & 0 deletions rmtt_tracker/launch/vrpn.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
<launch>

<arg name="server" default="localhost"/>

<node pkg="vrpn_client_ros" type="vrpn_client_node" name="vrpn_client_node" output="screen">
<rosparam subst_value="true">
server: $(arg server)
port: 3883

update_frequency: 100.0
frame_id: world

# Use the VRPN server's time, or the client's ROS time.
use_server_time: false
broadcast_tf: true

# Must either specify refresh frequency > 0.0, or a list of trackers to create
refresh_tracker_frequency: 1.0
trackers:
- FirstTracker
- SecondTracker
</rosparam>
</node>

</launch>

0 comments on commit c732ff8

Please sign in to comment.