From 952edc4438fc65745eda1a45298d745102546750 Mon Sep 17 00:00:00 2001 From: Jeffrey Date: Wed, 4 Dec 2019 14:16:53 -0500 Subject: [PATCH] merge conflict --- alternative_velodyne_setup.sh | 19 +++++++++++++++++++ cart_endpoints/scripts/motor_endpoint.py | 6 +++--- cart_endpoints/scripts/ros_client.py | 7 ++----- .../scripts/test_live_analysis_v2.py | 3 +-- velodyne_setup.sh | 17 +++++++++++++++++ 5 files changed, 42 insertions(+), 10 deletions(-) create mode 100755 alternative_velodyne_setup.sh create mode 100755 velodyne_setup.sh diff --git a/alternative_velodyne_setup.sh b/alternative_velodyne_setup.sh new file mode 100755 index 00000000..6bd46afd --- /dev/null +++ b/alternative_velodyne_setup.sh @@ -0,0 +1,19 @@ +#!/bin/bash + +echo "Running Different Velodyne Setup Script" + +echo "Shutting Down WiFi" + +nmcli radio wifi off + +sudo ifconfig eth0 up + +echo "Assigning IP to Port" + +sudo ip addr add 192.168.1.200 dev eth0 + +echo "Adding static route to LIDAR IP" + +sudo route add -net 192.168.1.0 netmask 255.255.255.0 dev eth0 + +echo "Try running the velodyne manager now" diff --git a/cart_endpoints/scripts/motor_endpoint.py b/cart_endpoints/scripts/motor_endpoint.py index 9fa124bb..e4b68ed8 100755 --- a/cart_endpoints/scripts/motor_endpoint.py +++ b/cart_endpoints/scripts/motor_endpoint.py @@ -28,8 +28,8 @@ def __init__(self): rospy.loginfo("Starting motor node!") #Connect to arduino for sending speed try: - rospy.loginfo("remove comments") - #self.speed_ser = serial.Serial(cart_port, 57600, write_timeout=0) + #rospy.loginfo("remove comments") + self.speed_ser = serial.Serial(cart_port, 57600, write_timeout=0) except Exception as e: print( "Motor_endpoint: " + str(e)) rospy.logerr("Motor_endpoint: " + str(e)) @@ -113,7 +113,7 @@ def send_to_motors(self): else: bitstruct.pack_into('u8u8u8u8u8', data, 0, 42, 21, abs(target_speed), 0, target_angle) - #self.speed_ser.write(data) + self.speed_ser.write(data) if __name__ == "__main__": diff --git a/cart_endpoints/scripts/ros_client.py b/cart_endpoints/scripts/ros_client.py index 8676f4eb..8cde29ff 100755 --- a/cart_endpoints/scripts/ros_client.py +++ b/cart_endpoints/scripts/ros_client.py @@ -50,9 +50,6 @@ def send_audio(msg): } send('audio',JSON.dumps(json)) -#audio call pullover -def sendPullOver(): - send('pull_over',id) #pose tracking send when unsafe def sendUnsafe(): @@ -65,7 +62,7 @@ def sendPassengerExit(): def sendReady(): send('passenger_ready',id) -def sendLocation(): +def sendLocation(self): send('current_location',id) @sio.on('pull_over',namespace='/cart') @@ -122,7 +119,7 @@ def status_update(data): def pullover_callback(msg): if msg.data == True: send_stop(True, 2) - sendPullOver() + sendUnsafe() else: send_stop(False, 2) sendReady() #is this how it should work?' diff --git a/cart_endpoints/scripts/test_live_analysis_v2.py b/cart_endpoints/scripts/test_live_analysis_v2.py index a6c0048d..cb0b8f23 100755 --- a/cart_endpoints/scripts/test_live_analysis_v2.py +++ b/cart_endpoints/scripts/test_live_analysis_v2.py @@ -21,7 +21,6 @@ from sklearn.ensemble import RandomForestClassifier import paho.mqtt.client as mqtt from std_msgs.msg import Int8, String, Bool -from navigation_msgs import EmergencyStop import json # Add openpose to system PATH and import @@ -153,7 +152,7 @@ def analyze(): #Analyze passenger safety. # Returns np array def safety_check(frame): - filename = 'full_dataset_model.sav' + filename = '/home/jeffercize/catkin_ws/src/ai-navigation/cart_endpoints/scripts/full_dataset_model.sav' loaded_model = pickle.load(open(filename, 'rb')) if (len(frame.shape) == 0): frame = np.zeros((1,75)) diff --git a/velodyne_setup.sh b/velodyne_setup.sh new file mode 100755 index 00000000..f9bc7b2c --- /dev/null +++ b/velodyne_setup.sh @@ -0,0 +1,17 @@ +#!/bin/bash + +echo "Running Velodyne Setup Script" + +echo "Shutting Down WiFi" + +nmcli radio wifi off + +echo "Assigning IP to Port" + +sudo ifconfig eno1 192.168.3.100 + +echo "Adding static route to LIDAR IP" + +sudo route add 192.168.1.201 eno1 + +echo "Try running the velodyne manager now"