diff --git a/Planning/planning_tools/carla_global_path.py b/Planning/planning_tools/carla_global_path.py new file mode 100644 index 0000000..35d4fa8 --- /dev/null +++ b/Planning/planning_tools/carla_global_path.py @@ -0,0 +1,74 @@ +import rospy +from sensor_msgs.msg import JointState +from geometry_msgs.msg import PoseStamped +import csv +import matplotlib +import threading +import math +rospy.init_node("carla_glodal_path") +class publisher: + def __init__(self): + self.x=0 + self.y=0 + self.nodes = [] + self.node_x = [] + self.node_y = [] + self.path_x = [] + self.path_y = [] + self.hz = rospy.Rate(20) + self.get_global_path() + self.path_pub = rospy.Publisher("/hdmap/path", JointState, queue_size = 1) + self.utm_sub = rospy.Subscriber("utm_fix", PoseStamped, self.utm_CallBack) + + self.id = 0 + self.len = 30 + Th1 = threading.Thread(target=self.publishing) + Th1.daemon = True + Th1.start() + rospy.spin() + def utm_CallBack(self, data): + self.x = data.pose.position.x + self.y = data.pose.position.y + + def get_global_path(self): + # name =raw_input("input carla path :") + name = "E6_path1.csv" + with open(name, "r") as f: + reader = csv.reader(f, delimiter = ',') + for rows in reader: + x = float(rows[0]) + y = float(rows[1]) + self.nodes.append([x,y]) + def publishing(self): + while self.x==0 or self.y==0: + rospy.loginfo("Waiting for start") + while not rospy.is_shutdown(): + id = 0 + msg = JointState() + for i in self.nodes: + #print( math.sqrt((i[0]-self.x)**2+(i[1] - self.y)**2), i, self.x, self.y) + if math.sqrt((i[0]-self.x)**2+(i[1] - self.y)**2) < 5: + self.id = id + break + id+=1 + else: + rospy.loginfo("Path is gone") + continue + k=2 + for i in range(self.id+k, self.id + self.len+k): + x = 0 + y = 0 + try: + x = self.nodes[i][0] + y = self.nodes[i][1] + except: + rospy.loginfo("# WARNING: Path end") + break + msg.position.append(x) + msg.velocity.append(y) + rospy.loginfo("publishing {}".format(self.id)) + rospy.sleep(0.05) + self.path_pub.publish(msg) + +if __name__ == "__main__": + a = publisher() diff --git a/Planning/planning_tools/move_Ioniq_Carla.py b/Planning/planning_tools/move_Ioniq_Carla.py new file mode 100644 index 0000000..964fb09 --- /dev/null +++ b/Planning/planning_tools/move_Ioniq_Carla.py @@ -0,0 +1,399 @@ +# Mediating Node for Ioniq, move_Ioniq +# Author: Juho Song (hoya4764@dgist.ac.kr) +# 2020.09.03 released +# version 1.0.3 +# github : + +# +# 1. every mode in this file can be used. +# 2. PID function has modified. + +# structure of move_car for Ioniq: [car_type = 0.0(Ioniq), mode, speed, accel, brake, steer, gear, angular(Ioniq), status(ERP42), estop(ERP42)] + +#for PID +import time + +#ros2 module +import rospy +from std_msgs.msg import Int16 +from std_msgs.msg import Float32MultiArray +from std_msgs.msg import Float64 +from std_msgs.msg import String + +NODENAME = "move_Ioniq" + +#subscribed topics +topic_Movecar = '/move_car' +topic_Info = '/Carla_info' +topic_NavPilot = '/mission_manager/nav_pilot' + +#topics to be published +topic_MovecarInfo = '/move_car_info' + +rootname = '/dbw_cmd' +topic_Accel = '/Accel' +topic_Angular = '/Angular' +topic_Brake = '/Brake' +topic_Steer = '/Steer' +topic_Gear = '/Gear' + +class Move_Ioniq(): + + def __init__(self): + # Initializing move_Ioniq node + + #callback data + self.infomsg = [] # Ioniq_info + self.cur_vel = 0.0 # Carla_info + self.move_carmsg = [] #move_car(debug) + self.move_car_info = "" #move_car_info + self.prev_mode = 200.0 + self.nav_pilot_switch = 2 + + # About PID + self.cur_time = time.time() + self.prev_time = 0 + self.del_time = 0 + self.kp = 20 + self.ki = 7 + self.kd = 5 + self.error_p = 0 + self.error_i = 0 + self.error_d = 0 + self.prev_error = 0 + self.antiwindup = 70 + self.prev_desired_vel = 0 + self.mode_data = [None] * 4 + + # Initializing Ioniq dbw_cmd_node publisher + self.accelPub = rospy.Publisher(rootname + topic_Accel, Int16, queue_size = 1) + self.brakePub = rospy.Publisher(rootname + topic_Brake, Int16,queue_size = 1) + self.steerPub = rospy.Publisher(rootname + topic_Steer, Int16,queue_size = 1) + self.gearPub = rospy.Publisher(rootname + topic_Gear, Int16,queue_size = 1) + self.angularPub = rospy.Publisher(rootname + topic_Angular, Int16,queue_size = 1) + + # Initializing dbw_ioniq_node subscriber + self.InfoSub = rospy.Subscriber(topic_Info, Float32MultiArray, self.info_callback) + + # Initializing Navigation Pilot switch subscriber + self.NavPilotSub = rospy.Subscriber(topic_NavPilot, Int16, self.nav_pilot_callback) + + # Initializing move_car topic subscriber + self.move_carSub = rospy.Subscriber(topic_Movecar,Float32MultiArray, self.move_car_callback) + + # Initializing move_car_info topic publisher (depends on move_car callback) + self.MovecarInfoPub = rospy.Publisher(topic_MovecarInfo, String, queue_size = 1) + rospy.spin() + def nav_pilot_callback(self, msg): + self.nav_pilot_switch = msg.data + + def info_callback(self, msg): + self.cur_vel = msg.data[0] + + if self.mode_data[0] == 1.0 or self.mode_data[0] == 2.0 or self.mode_data[0] ==4.0 or self.mode_data[0] ==5.0 or self.mode_data[0] ==6.0: # for PID + self.mode_data[2], self.mode_data[3] = self.PID(self.mode_data[1]) + self.pub_accel(self.mode_data[2]) + self.pub_brake(self.mode_data[3]) + self.mode_data[1] = self.prev_desired_vel + rospy.loginfo("cruise mode{}. {}km/h a: {}, b: {}".format(self.mode_data[0], self.mode_data[1], self.mode_data[2],self.mode_data[3])) + + # structure of move_car for Ioniq: [car_type = 0.0(Ioniq), mode, speed, accel, brake, steer, gear, angular(Ioniq), status(ERP42), estop(ERP42)] + def move_car_callback(self, msg): + rospy.loginfo("{}".format(msg.data)) + if self.prev_mode == 200.0 and len(msg.data) ==1 and msg.data[0] == 119.0: #case 0. when the reset code is the first published code + self.prev_mode == 119.0 + rospy.logwarn("You published E-Stop reset code as the first topic!") + + elif self.prev_mode == 119.0 and len(msg.data) ==1 and msg.data[0] == 119.0: #case 1. reset many times repeatly + self.prev_mode = 119.0 + rospy.logwarn("Don't reset too much!") + + elif self.prev_mode !=0.0 and len(msg.data) == 1 and msg.data[0] == 119.0: #case 2. reset after other modes except E-Stop mode + self.prev_mode = 119.0 + rospy.logwarn("Reset after other modes except E-Stop mode.") + + elif self.prev_mode !=0.0: + + if len(msg.data) != 10 or msg.data[0] != 0.0: #wrong topics + rospy.logwarn("You published wrong!!! {}".format(msg.data)) + else: + mode = msg.data[1] + + if self.nav_pilot_switch == 0 and mode == 6.0: # mission manager mode + if self.prev_mode == 119.0: + self.emergency_stop_off() + steer = msg.data[5] + gear = msg.data[6] + angular = msg.data[7] + + self.cruise_control(msg) + self.pub_gear(gear) + self.pub_angular(angular) + self.pub_steer(steer) + self.prev_mode = msg.data[1] + self.move_carmsg = msg.data #debug + rospy.loginfo("{}".format(self.move_carmsg)) #dubug + + elif mode ==0.0: #E-STOP + rospy.logwarn("E-STOP Publishing Actuator with mode{}".format(mode)) + self.emergency_stop_on() + self.mode_data[0] = 0.0 + self.prev_mode = msg.data[1] + self.move_carmsg = msg.data #debug + rospy.loginfo("{}".format(self.move_carmsg)) #dubug + self.prev_error = 0 + self.error_i = 0 + self.prev_time = 0 + self.prev_desired_vel = 0 + + elif mode == 1.0: #cruise control + if self.prev_mode == 119.0: + self.emergency_stop_off() + self.cruise_control(msg) + self.prev_mode = msg.data[1] + self.move_carmsg = msg.data #debug + rospy.loginfo("{}".format(self.move_carmsg)) #dubug + + elif mode == 2.0: #cruise control with steering + + if self.prev_mode == 119.0: + self.emergency_stop_off() + steer = msg.data[5] + angular = msg.data[7] + + self.cruise_control(msg) + self.pub_angular(angular) + self.pub_steer(steer) + self.prev_mode = msg.data[1] + self.move_carmsg = msg.data #debug + rospy.loginfo("{}".format(self.move_carmsg)) #dubug + + elif mode == 3.0: # mode that you can directly publish cmd value (for develper mode.) + + if self.prev_mode == 119.0: + self.emergency_stop_off() + self.mode_data[0] = 3.0 + accel = msg.data[3] + brake = msg.data[4] + steer = msg.data[5] + gear = msg.data[6] + angular = msg.data[7] + + self.pub_accel(accel) + self.pub_brake(brake) + self.pub_gear(gear) + self.pub_angular(angular) + self.pub_steer(steer) + self.prev_mode = msg.data[1] + self.move_carmsg = msg.data #debug + rospy.loginfo("{}".format(self.move_carmsg)) #dubug + self.prev_error = 0 + self.error_i = 0 + self.prev_desired_vel = 0 + self.prev_time = 0 + + elif mode == 4.0: # mode 1.0 + mode 3.0 (cruise control and direct publish except accel and brake) + + if self.prev_mode == 119.0: + self.emergency_stop_off() + steer = msg.data[5] + gear = msg.data[6] + angular = msg.data[7] + + self.cruise_control(msg) + self.pub_gear(gear) + self.pub_angular(angular) + self.pub_steer(steer) + self.prev_mode = msg.data[1] + self.move_carmsg = msg.data #debug + rospy.loginfo("{}".format(self.move_carmsg)) #dubug + + elif mode == 5.0: # navigation pilot mode + if self.nav_pilot_switch == 0: #switch off + rospy.logwarn("nav_pilot_switch is off!") + + elif self.nav_pilot_switch ==1: + if self.prev_mode == 119.0: + self.emergency_stop_off() + steer = msg.data[5] + gear = msg.data[6] + angular = msg.data[7] + + self.cruise_control(msg) + self.pub_gear(gear) + self.pub_angular(angular) + self.pub_steer(steer) + self.prev_mode = msg.data[1] + self.move_carmsg = msg.data #debug + rospy.loginfo("{}".format(self.move_carmsg)) #dubug + + elif self.prev_mode == 0.0: + + if len(msg.data) == 1 and msg.data[0] ==119.0: #escape code [119.0] + self.prev_mode = 119.0 + rospy.loginfo("Escape!") + else: + rospy.loginfo("Stucked in E-Stop! {}".format(msg.data)) + + else: + rospy.logwarn("Not Valid Message!!! {}".format(msg.data)) + + + + + # Basic cmd publisher + def pub(self, topic, val): + topic_list = ['accel','brake','steer','gear','angular'] + + if topic == topic_list[0]: + val = int(val) + if not 0 <= val <= 3000: + raise ValueError("your val for accel, {} is out of range.".format(val)) + accel = Int16() + accel.data = val + self.accelPub.publish(accel) + + elif topic == topic_list[1]: + val = int(val) + if not 0 <= val <= 29000: + raise ValueError("your val for brake, {} is out of range.".format(val)) + brake = Int16() + brake.data = val + self.brakePub.publish(brake) + + elif topic == topic_list[2]: + val = int(val) + if not -440 <= val <= 440: + raise ValueError("your val for steer, {} is out of range.".format(val)) + steer = Int16() + steer.data = val + self.steerPub.publish(steer) + + elif topic == topic_list[3]: + val = int(val) + gear_dict = {0:"parking",5:"driving",6:"neutral",7:"reverse"} + if val not in gear_dict: + raise ValueError("your val for gear, {} is not valid.".format(val)) + gear = Int16() + gear.data = val + self.gearPub.publish(gear) + + elif topic == topic_list[4]: + val = int(val) + if not 0 <= val <= 255: + raise ValueError("your val for angular, {} is out of range.".format(val)) + angular = Int16() + angular.data = val + self.angularPub.publish(angular) + + #Functional cmd publishers + def pub_accel(self, val): + self.pub('accel', val) + + def pub_brake(self, val): + self.pub('brake', val) + + def pub_steer(self, val): + self.pub('steer', val) + + def pub_gear(self, val): + self.pub('gear', val) + + def pub_angular(self, val): + self.pub('angular', val) + + #mode manager + + #mode 0. Emergency Stop + def emergency_stop_on(self, msg): + self.pub_accel(0.0) + self.pub_brake(29000.0) + + def emergency_stop_off(self): + rospy.loginfo("E-Stop Off!") + + #mode 1. Cruise Control + def PID(self,desired_vel): + + if desired_vel == -1.0: + desired_vel = self.prev_desired_vel + + # When desired velocity is changed, prev_error and error_i should be reset! + if desired_vel != self.prev_desired_vel: + self.prev_error = 0 + self.error_i = 0 + self.prev_time = 0 + self.prev_desired_vel = desired_vel + + # Defining dt(del_time) + self.cur_time = time.time() + if self.prev_time ==0: + self.del_time = 0 + elif self.prev_time!=0: + self.del_time = self.cur_time - self.prev_time + + # Calculate Errors + self.error_p = desired_vel - self.cur_vel + self.error_i += self.error_p * (self.del_time) + time.sleep(0.005) + if (self.error_i < - self.antiwindup): + self.error_i = - self.antiwindup + elif (self.error_i > self.antiwindup): + self.error_i = self.antiwindup + if self.prev_time ==0: + self.error_d = 0 + elif self.prev_time!=0: + self.error_d = (self.error_p - self.prev_error)/self.del_time + + # PID Out + pid_out = self.kp*self.error_p + self.ki*self.error_i + self.kd*self.error_d + self.pid_out = pid_out + if pid_out > 1000: + pid_out = 1000 + elif pid_out < -1000: + pid_out = -1000 + + self.prev_error = self.error_p # Feedback current error + self.prev_time = self.cur_time # Feedback current time + + # accel_max - accel_dead_zone = 3000 - 800 = 2200 + # 2200/10 = 220, 220 + 1 = 221 + ''' + if pid_out > 0: + for i in range(221): + if i <= pid_out < i+1: + return 800 + 10*i, 0 + ''' + if pid_out > 0: + for i in range(858): + if i <= pid_out < i+1: + gaspedal = 800 + 10*i + if gaspedal >= 3000: + gaspedal = 3000 + return gaspedal, 0 + else: + return gaspedal, 0 + + + # brake_max - brake_dead_zone = 29000 - 3500 = 25500 (!!!!!!!should be changed to 29000 if needed!!!!!!!) + # 25500/10 = 2550, 2550 + 1 = 2551 + elif pid_out < 0: + for i in range(2551): + if i <= abs(pid_out) < i+1: + return 0, 2700+10*i + + return 0, 0 + + def cruise_control(self,msg): + self.mode_data = [msg.data[1], msg.data[2], 0.0, 0.0] #[mode, target_speed, 0.0, 0.0] + +def main(): + rospy.init_node(NODENAME) + move_car = Move_Ioniq() + + # Destroy the node explicitly + # (optional - otherwise it will be done automatically + # when the garbage collector destroys the node object) + +if __name__ == '__main__': + main() diff --git a/Planning/planning_tools/path_viewer.py b/Planning/planning_tools/path_viewer.py new file mode 100644 index 0000000..3db4e50 --- /dev/null +++ b/Planning/planning_tools/path_viewer.py @@ -0,0 +1,176 @@ +import csv +import utm +import argparse +import math +import matplotlib.pyplot as plt + +from pyproj import Proj, transform +import numpy as np +import pandas as pd +# Projection 정의 +# UTM-K +proj_UTMK = Proj(init='epsg:5178') # UTM-K(Bassel) 도로명주소 지도 사용 중 + +# WGS1984 +proj_WGS84 = Proj(init='epsg:4326') # Wgs84 경도/위도, GPS사용 전지구 좌표 +class modified_path: + def __init__(self, input_path= '', output_path= ''): + self.x_path = [] + self.y_path = [] + self.latlon=[] + self.utm_files = ["/home/vision/Desktop/path/parking1.csv"]#,"/home/vision/Desktop/path/parking2-1.csv","/home/vision/Desktop/path/parking3.csv","/home/vision/Desktop/path/parking4-2.csv","/home/vision/Desktop/path/parking5.csv","/home/vision/Desktop/path/parking6-1.csv"] + self.gps_files= ["/home/vision/k_parking_start1_p.csv","/home/vision/k_parking_start2_p.csv","/home/vision/k_parking_start3_p.csv"] + #,"/home/vision/k_parking_start2_p.csv","/home/vision/k_parking_start3_p.csv" + self.off = 3 + self.x_point = [] + self.y_point = [] + self.buff = [] + for file in self.utm_files: + self.get_utm_path(file,self.x_path,self.y_path) + + for file in self.gps_files: + self.get_gps_path(file, self.x_point, self.y_point) + print("path size :", len(self.x_point)) + ''' + for file in self.gps_files: + self.get_gps_path1(file, self.x_point, self.y_point) + print("path size :", len(self.x_point)) + ''' + self.fig, self.ax = plt.subplots(figsize=(15, 8)) + plt.grid(True) + plt.xlabel('x') + plt.ylabel('y') + plt.title('Interactive Plot') + + self.ax.set(xlim=[min(self.x_path+self.x_point)-self.off, max(self.x_path+self.x_point)+self.off], ylim=[min(self.y_path+self.y_point)-self.off, max(self.y_path+self.y_point)+self.off]) + self.ax.set_aspect(1, adjustable='box') + + self.line, = self.ax.plot(self.x_path, self.y_path, "bo") + self.cid = self.fig.canvas.mpl_connect('button_press_event', self.add_point) + plt.show() + def add_point(self, event): + #print('you pressed', event.key, event.xdata, event.ydata) + if event.inaxes != self.ax: + return + + x = event.xdata + y = event.ydata + + if event.button == 1 : + if event.key == 'shift': + id1, id2 = self.get_point_id(x,y) + if id1>id2: + self.x_path.insert(id1,x) + self.y_path.insert(id1,y) + else: + self.x_path.insert(id2,x) + self.y_path.insert(id2,y) + + if event.key =='control': + plt.plot(self.x_point, self.y_point, "go") + + self.line.set_data(self.x_path, self.y_path) + plt.draw() + + + if event.button == 3: + if event.key == 'shift': + id1, id2= self.get_point_id(x,y) + self.buff.append([id1, self.x_path[id1], self.y_path[id1]]) + del self.x_path[id1] + del self.y_path[id1] + if event.key =='control': + try: + self.x_path.insert(self.buff[-1][0], self.buff[-1][1]) + self.y_path.insert(self.buff[-1][0], self.buff[-1][2]) + self.buff.pop() + except: + print("Don't Ctrl z") + self.line.set_data(self.x_path, self.y_path) + plt.draw() + + + if event.button == 2: + self.save_point() + plt.disconnect(self.cid) + plt.close() + + def get_utm_path(self,file_name,x_path,y_path): + + print("start read path :",file_name) + p=[0,0] + with open(file_name, "r") as f: + reader = csv.reader(f) + for raw in reader: + x_path.append(float(raw[0])) + y_path.append(float(raw[1])) + + print(raw[0], raw[1],395201.3103811303, 5673135.241182375 ) + #p=utm.to_latlon(raw[0], raw[1]) + self.latlon.append([p[0],p[1]]) + #print(p) + print ("path size :", len(self.x_path)) + def get_gps_path1(self,file_name, x_path,y_path): + cnt = 0 + print("start read path :",file_name) + proj_UTMK = Proj(init='epsg:5178') # UTM-K(Bassel) 도로명주소 지도 사용 중 + + # WGS1984 + proj_WGS84 = Proj(init='epsg:4326') # Wgs84 경도/위도, GPS사용 전지구 좌표 + with open(file_name, "r") as f: + reader = csv.reader(f) + x=0 + y=0 + for raw in reader: + + if cnt==0: + cnt = 1 + continue + x,y=transform(proj_WGS84, proj_UTMK, float(raw[7]), float(raw[6])) + x_path.append(x) + y_path.append(y) + def get_gps_path(self,file_name, x_path,y_path): + cnt = 0 + print("start read path :",file_name) + with open(file_name, "r") as f: + reader = csv.reader(f) + p = [0,0] + for raw in reader: + if cnt==0: + cnt = 1 + continue + p = utm.from_latlon(float(raw[6]), float(raw[7])) + x_path.append(p[0]) + y_path.append(p[1]) + + def get_point_id(self, x, y): + first_id = -1 + second_id = -1 + mind1 = 100000000000000 + mind2 = 100000000000000 + for i in range(len(self.x_path)): + d = math.sqrt((self.x_path[i]-x)*(self.x_path[i]-x) + (self.y_path[i]-y)*(self.y_path[i]-y)) + if(d