diff --git a/.gitignore b/.gitignore index f3ba52fc..2f5b26af 100644 --- a/.gitignore +++ b/.gitignore @@ -1,3 +1,8 @@ -results/ +/results/* +!/results/postProcess.py +!/results/README.md /docs/build -/docs/Manifest.toml +docs/Manifest.toml +/knitro-10.3.0-z-Linux-64/* +artelys_lic_404_umich_mecheng_mm_2017-03-27_knitro_73-34-b5-18-fc.txt +artelys_lic_897_umich_mecheng_mm_2018-02-06_knitro_1a-af-55-b8-be.txt diff --git a/Dockerfile b/Dockerfile index ad3e24f0..72019375 100644 --- a/Dockerfile +++ b/Dockerfile @@ -1,7 +1,21 @@ FROM avpg/cain:middle +RUN /bin/bash -c 'rm -rf /home/$USERNAME/MAVs/ros/devel/* /home/$USERNAME/MAVs/ros/build/*' + COPY ros /home/$USERNAME/MAVs/ros RUN /bin/bash -c 'source /opt/ros/kinetic/setup.bash; cd /home/$USERNAME/MAVs/ros/; catkin_make' +#COPY knitro-10.3.0-z-Linux-64 /home/$USERNAME/knitro-10.3.0-z-Linux-64 +#RUN echo 'export PATH="$HOME/knitro-10.3.0-z-Linux-64/knitroampl:$PATH"' >> ~/.bashrc +#RUN echo 'export LD_LIBRARY_PATH="$HOME/knitro-10.3.0-z-Linux-64/lib:$LD_LIBRARY_PATH"' >> ~/.bashrc +#RUN /bin/bash -c 'sudo chmod -R a+rX /home/mavs/knitro-10.3.0-z-Linux-64/*' + +# laptop +# COPY artelys_lic_897_umich_mecheng_mm_2018-02-06_knitro_1a-af-55-b8-be.txt /home/$USERNAME/ +#COPY artelys_lic_897_umich_mecheng_mm_2018-02-06_knitro_1a-af-55-b8-be.txt /home/$USERNAME/ + +# home +#COPY artelys_lic_404_umich_mecheng_mm_2017-03-27_knitro_73-34-b5-18-fc.txt /home/$USERNAME/ + # Default CMD CMD ["/bin/bash"] diff --git a/README.md b/README.md index 0f477860..6ad01cdc 100644 --- a/README.md +++ b/README.md @@ -15,7 +15,7 @@ Or for the develop branch ``` git clone -b develop https://github.com/JuliaMPC/MAVs ``` -Then follow the [Docker instructions](https://github.com/JuliaMPC/MAVs/tree/master/docker#mavs-docker). +Then follow the [Docker instructions](https://github.com/JuliaMPC/MAVs/tree/develop/image/cain). * Note: currently, the entire repo is cloned twice (once by the above command and once by the Docker file). * In the future this software may be configured to save space and only cloned once diff --git a/docs/make.jl b/docs/make.jl index 143a2f15..b63b18a9 100644 --- a/docs/make.jl +++ b/docs/make.jl @@ -29,7 +29,6 @@ pages = [ "system_shutdown" => "packages/system/system_shutdown.md", "data_logging" => "packages/system/data_logging.md", "chrono_position_broadcaster" => "packages/model/chrono/chrono_position_broadcaster/main.md", - "ros_chrono_msgs" => "packages/model/chrono/ros_chrono_msgs/main.md", "point_cloud_converter" => "packages/computing/perception/point_cloud_converter.md", ], "System demos" => [ diff --git a/docs/src/packages/model/chrono/ros_chrono_msgs/main.md b/docs/src/packages/model/chrono/ros_chrono_msgs/main.md deleted file mode 100644 index 493cb528..00000000 --- a/docs/src/packages/model/chrono/ros_chrono_msgs/main.md +++ /dev/null @@ -1,18 +0,0 @@ -# ros_chrono_msgs -Creates a `ROS` msg file veh_status.msg to observe vehicle states during runtime of `Chrono` model. Used by the ros_chrono package. - -## Message format -Name | Variable | Description ---- | --- -`float64` | t_chrono | simulation time -`float64` | x_pos | vehicle x position -`float64` | y_pos | vehicle y position -`float64` | x_v | vehicle velocity in x (m/s) -`float64` | x_a | vehicle acceleration in x (m/s^2) -`float64` | y_v | vehicle velocity in y -`float64` | yaw_curr | current yaw value (rad) -`float64` | yaw_rate | current yaw rate (rad/s) -`float64` | sa | steering angle (rad) -`float64` | thrt_in | throttle control input -`float64` | brk_in | brake control input -`float64` | str_in | steering control input diff --git a/results/README.md b/results/README.md index 12e7dda0..927d734c 100644 --- a/results/README.md +++ b/results/README.md @@ -1,4 +1,10 @@ # Results Directory This directory share files between local host and container -It is used to store results data -Do not delete this directory +It is used to store results data. +[bag name] should be in format of like demoK_s4_D.bag, where demoK is the demo name, s4 is the case name, and D is the planner name. + +to get .csv files with case information: python run_data.py [bag name] [csv_path_name] + [csv_path_name] is optional, the default value is ./test + +to get .csv files: python postProcess.py [bag_name1] [bagname2] [bagname3] + [bag_name1] [bagname2] [bagname3] are optional, the default value is all files in the current folder diff --git a/results/postProcess.py b/results/postProcess.py new file mode 100755 index 00000000..946c69ef --- /dev/null +++ b/results/postProcess.py @@ -0,0 +1,284 @@ +#!/usr/bin/python +import sys +import csv +import rosbag +import io +import os + +def bag2csv(bag_name): + + csv_name = bag_name.rstrip('.bag') + + # open bag file for read + print "Reading " + bag_name + bag = rosbag.Bag(bag_name) + bag_topics = bag.get_type_and_topic_info()[1].keys() + + # open csv file for write + csvfile = open(csv_name+'.csv', 'w') + #bag2csv = csv.writer(csvfile, delimiter=';', quotechar='\'', quoting=csv.QUOTE_MINIMAL) + bag2csv = csv.writer(csvfile, delimiter=',', quotechar='\'', quoting=csv.QUOTE_MINIMAL) + + for bag_topic in bag_topics: + # write topic name + print "Write " + bag_topic + " into csv file..." + bag2csv.writerow([bag_topic]) + # set title_flag to 0 + title_flag = 0 + + for topic, msg, t in bag.read_messages(topics=bag_topic): + # split msg + msg_list = str(msg).split('\n') + value_list = [] + title_list = [] + + for msg_pair in msg_list: + split_pair = msg_pair.split(':') + msg_title = split_pair[0] + msg_value = split_pair[1] + + if title_flag == 0: + title_list.append(msg_title) + value_list.append(msg_value) + + if title_flag == 0: + bag2csv.writerow(title_list) + title_flag = 1 + + bag2csv.writerow(value_list) + + # insert a row between to topics + bag2csv.writerow([]) + + + # close files + csvfile.close() + bag.close() + return csv_name+'.csv' + + +def processcsv(pathname, csvfilename): + csvfilename_full = csvfilename + statefilename_full = os.path.join(pathname, "state.csv") + tempfilename_full = os.path.join(pathname, "temp.csv") + F = open(csvfilename_full, 'r') + F_w = open(statefilename_full, 'w') + F_w1 = open(tempfilename_full, 'w') + + old = F.read() + F.seek(0,0) + old1 = F.read() + F.seek(0,0) + old2 = F.read() + # copy the whole input F file and remove all the [] and replaced that with ; for state + old = old.replace("[", "") + old = old.replace("]", "") + #old = old.replace(",", ";") + # copy the whole input F file and remove all the [] and replaced that with ; for planned + old1 = old1.replace("[", "") + old1 = old1.replace("]", "") + #old1 = old1.replace(",", ";") + # copy the whole input F file and remove all the [] and replaced that with ; for control + old2 = old2.replace("[", "") # for control information + old2 = old2.replace("]", "") + #old2 = old2.replace(",", ";") + + # Find the start position for three topics: /state, /opt, /control + result = old.find("state") + result1 = old1.find("/opt") + result2 = old1.find("/nlopcontrol_planner/control") + old = old[result+7:len(old)] + old = old.replace("tire_f", "vtffr,vtffl,vtfrr,vtfrl") + old1 = old1[result1+6:result2] + old1 = old1.replace("X0p,X0a,X0e", "x,y,v,r,psi,sa,ux,ax") + old2 = old2[result2+30:result] + + # The first step cleaned values for three topics in total are written in F_w1 for latter use + # State information is already good to go and store in F_w + F_w.truncate(0) + F_w.write(old) + F_w1.truncate(0) + F_w1.write(old1) + F_w1.seek(0,0) + F_w1.close() + + # Continue to process planned csv + F_w1 = open(tempfilename_full, 'r') + plannedfilename_full = os.path.join(pathname, "planned.csv") + F_w2 = open(plannedfilename_full, 'w') + old = "" + count = 0 + line = F_w1.readline() + cnt = 1 + se = list() + ve = list() + old = line + while line: + line = F_w1.readline() + temp = line.split(',',28) + old = old + '\n' + try: + for i in xrange(0,11): + old = old + temp[i] + ',' + old = old + temp[11] + se.append(temp[25]) + ve.append(temp[26]) + except: + pass + cnt += 1 + F_w2.truncate(0) + F_w2.write(old) + F_w1.close() + + # Continue to process control csv + controlfilename_full = os.path.join(pathname, "miscResults.csv") + F_w1 = open(tempfilename_full, 'w') + F_w1.truncate(0) + F_w1.write(old2) + F_w1.close() + F_w1 = open(tempfilename_full, 'r') + F_w3 = open(controlfilename_full, 'w') + old = "" + count = 0 + line = F_w1.readline() + cnt = 0 + vce = 0.0 # Acc control effort + sce = 0.0 # Steering control effort + vce_accum = 0.0 # accumulated value for acc control effort + sce_accum = 0.0 # accumulated value for steering control effort + old = line[0:-2] + ',ceStr' + ',ceAcc' + ',teStr' + ',teU' # se is the steering error and ve is the acc error + while line: + line = F_w1.readline() + temp = line.split(',',11*16-1) + # print temp + old = old + '\n' + try: + for i in xrange(0,11): + old = old + temp[i*16] + ', ' + sce_accum = sce_accum + abs(float(temp[6 * 16])) + vce_accum = vce_accum + abs(float(temp[8 * 16])) + sce = vce_accum/(float(temp[0]) + 0.5) # Normalize the velocity control effort by time + vce = sce_accum/(float(temp[0]) + 0.5) # Normalize the steering control effort by time + old = old + str(sce) + ' , ' # Concatenate the normalized acc control effort + old = old + str(vce) + ' , ' # Concatenate the normalized steering control effort + old = old + se[cnt] + ' , ' + old = old + ve[cnt] + + except: + pass + cnt += 1 + F_w3.truncate(0) + F_w3.write(old) + F_w1.close() + F_w3.close() + # Remove last several lines for control, because there are several redudant symbols + F_w3 = open(controlfilename_full, 'r') + lines = F_w3.readlines() + F_w3.close() + F_w3 = open(controlfilename_full, 'w') + F_w3.writelines([item for item in lines[:-3]]) + F_w3.close() + # Remove last several lines for planned, because there are several redudant symbols + F_w2 = open(plannedfilename_full, 'r') + lines = F_w2.readlines() + F_w2.close() + F_w2 = open(plannedfilename_full, 'w') + F_w2.writelines([item for item in lines[:-2]]) + F_w2.close() + os.remove(tempfilename_full) + os.remove(csvfilename_full) + + +# save sX.ymal +def readcase(demoname, casename, plannername, pathname): + configpath = "../ros/src/system/config/case/" + sxfile= configpath+casename+".yaml" + print("Reading "+casename+".yaml ...") + casefilename_full = os.path.join(pathname, "case.csv") + + F_sx = open(sxfile, 'r') + F_w = open(casefilename_full, 'w') + + line = F_sx.readline() + + name = "" + value = "" + while line: + line = str(line) + if len(line) > 1: + if line[1]!=' ': + line = line[1:-1] + line = line.split(":") + name1 = line[0] + elif line[2]!=' ': + line = line[2:] + line = line.split(":") + name2 = line[0] + if(name2[0] <= 'z' and name2[0] >= 'a'): + name2 = name2[0].upper()+name2[1:] + for char2 in name2: + if(char2 == '0'): + char2 = 'O' + if(len(line) > 1): + value2 = line[1] + value2 = value2[0:-1] + + + if(len(value2) > 0): + name = name + name1 + name2 + ',' + value = value + value2 + ',' + + elif line[3]!=' ': + line = line[3:] + line = line.split(": ") + name3 = line[0] + value3 = line[1] + + if(name3[0] <= 'z' and name3[0] >= 'a'): + name3 = name3[0].upper()+name3[1:] + for char3 in name3: + if(char3 == '0'): + char3 = 'O' + + name = name + name1 + name2 + name3 + ',' + value3 = value3.replace(",", " ") + value = value + value3[0:-1] + ',' + + + line = F_sx.readline() + value = name+'\n'+value + F_w.truncate(0) + #F_w.writelines(name) + F_w.write(value) + F_sx.close() + F_w.close() + print "Finished!" + + +if __name__ == '__main__': + # handle result information + print "Start to convert rosbag to csv: " + bag_name = sys.argv[1] + print("filename: "+bag_name) + tempname = str(sys.argv[1]).split("_") + demoname = tempname[0] + casename = tempname[1] + plannername = tempname[2] + print(demoname+" "+casename+" "+plannername) + + if len(sys.argv) == 2: + pathname = "test" + else: + pathname = str(sys.argv[2]) + + pathname = "./"+pathname+"/"+casename+plannername + print("save files to: " + pathname) + + # make dir + #dirname = os.path.dirname(filename) + if not os.path.exists(pathname): + os.makedirs(pathname) + + filename = bag2csv(bag_name) + processcsv(pathname, filename) + readcase(demoname, casename, plannername, pathname) diff --git a/results/rosbag2csv.py b/results/rosbag2csv.py deleted file mode 100755 index 5ae0954c..00000000 --- a/results/rosbag2csv.py +++ /dev/null @@ -1,54 +0,0 @@ -#!/usr/bin/python -import sys -import csv -import rosbag - -if __name__ == '__main__': - print "Start to convert rosbag to csv" - bag_name = sys.argv[1] - csv_name = bag_name.rstrip('.bag') - - # open bag file for read - print "Reading " + bag_name - bag = rosbag.Bag(bag_name) - bag_topics = bag.get_type_and_topic_info()[1].keys() - - # open csv file for write - csvfile = open(csv_name+'.csv', 'w') - bag2csv = csv.writer(csvfile, delimiter=';', quotechar='\'', quoting=csv.QUOTE_MINIMAL) - - for bag_topic in bag_topics: - # write topic name - print "Write " + bag_topic + " into csv file..." - bag2csv.writerow([bag_topic]) - # set title_flag to 0 - title_flag = 0 - - for topic, msg, t in bag.read_messages(topics=bag_topic): - # split msg - msg_list = str(msg).split('\n') - value_list = [] - title_list = [] - - for msg_pair in msg_list: - split_pair = msg_pair.split(':') - msg_title = split_pair[0] - msg_value = split_pair[1] - - if title_flag == 0: - title_list.append(msg_title) - value_list.append(msg_value) - - if title_flag == 0: - bag2csv.writerow(title_list) - title_flag = 1 - - bag2csv.writerow(value_list) - - # insert a row between to topics - bag2csv.writerow([]) - - print "Finished!" - # close files - csvfile.close() - bag.close() \ No newline at end of file diff --git a/results/rundata.py b/results/rundata.py new file mode 100755 index 00000000..4d17ab9f --- /dev/null +++ b/results/rundata.py @@ -0,0 +1,286 @@ +#!/usr/bin/python +import sys +import csv +import rosbag +import io +import os + +def bag2csv(bag_name): + + csv_name = bag_name.rstrip('.bag') + + # open bag file for read + print "Reading " + bag_name + bag = rosbag.Bag(bag_name) + bag_topics = bag.get_type_and_topic_info()[1].keys() + + # open csv file for write + csvfile = open(csv_name+'.csv', 'w') + #bag2csv = csv.writer(csvfile, delimiter=';', quotechar='\'', quoting=csv.QUOTE_MINIMAL) + bag2csv = csv.writer(csvfile, delimiter=',', quotechar='\'', quoting=csv.QUOTE_MINIMAL) + + for bag_topic in bag_topics: + # write topic name + print "Write " + bag_topic + " into csv file..." + bag2csv.writerow([bag_topic]) + # set title_flag to 0 + title_flag = 0 + + for topic, msg, t in bag.read_messages(topics=bag_topic): + # split msg + msg_list = str(msg).split('\n') + value_list = [] + title_list = [] + + for msg_pair in msg_list: + split_pair = msg_pair.split(':') + msg_title = split_pair[0] + msg_value = split_pair[1] + + if title_flag == 0: + title_list.append(msg_title) + value_list.append(msg_value) + + if title_flag == 0: + bag2csv.writerow(title_list) + title_flag = 1 + + bag2csv.writerow(value_list) + + # insert a row between to topics + bag2csv.writerow([]) + + + # close files + csvfile.close() + bag.close() + return csv_name+'.csv' + + +def processcsv(pathname, csvfilename): + csvfilename_full = csvfilename + statefilename_full = os.path.join(pathname, "state.csv") + tempfilename_full = os.path.join(pathname, "temp.csv") + F = open(csvfilename_full, 'r') + F_w = open(statefilename_full, 'w') + F_w1 = open(tempfilename_full, 'w') + + old = F.read() + F.seek(0,0) + old1 = F.read() + F.seek(0,0) + old2 = F.read() + # copy the whole input F file and remove all the [] and replaced that with ; for state + old = old.replace("[", "") + old = old.replace("]", "") + #old = old.replace(",", ";") + # copy the whole input F file and remove all the [] and replaced that with ; for planned + old1 = old1.replace("[", "") + old1 = old1.replace("]", "") + #old1 = old1.replace(",", ";") + # copy the whole input F file and remove all the [] and replaced that with ; for control + old2 = old2.replace("[", "") # for control information + old2 = old2.replace("]", "") + #old2 = old2.replace(",", ";") + + # Find the start position for three topics: /state, /opt, /control + result = old.find("state") + result1 = old1.find("/opt") + result2 = old1.find("/nlopcontrol_planner/control") + old = old[result+7:len(old)] + old = old.replace("tire_f", "vtffr,vtffl,vtfrr,vtfrl") + old1 = old1[result1+6:result2] + old1 = old1.replace("X0p,X0a,X0e", "x,y,v,r,psi,sa,ux,ax") + old2 = old2[result2+30:result] + + # The first step cleaned values for three topics in total are written in F_w1 for latter use + # State information is already good to go and store in F_w + F_w.truncate(0) + F_w.write(old) + F_w1.truncate(0) + F_w1.write(old1) + F_w1.seek(0,0) + F_w1.close() + + # Continue to process planned csv + F_w1 = open(tempfilename_full, 'r') + plannedfilename_full = os.path.join(pathname, "planned.csv") + F_w2 = open(plannedfilename_full, 'w') + old = "" + count = 0 + line = F_w1.readline() + cnt = 1 + se = list() + ve = list() + old = line + while line: + line = F_w1.readline() + temp = line.split(',',28) + old = old + '\n' + try: + for i in xrange(0,11): + old = old + temp[i] + ',' + old = old + temp[11] + se.append(temp[25]) + ve.append(temp[26]) + except: + pass + cnt += 1 + F_w2.truncate(0) + F_w2.write(old) + F_w1.close() + + # Continue to process control csv + controlfilename_full = os.path.join(pathname, "miscResults.csv") + F_w1 = open(tempfilename_full, 'w') + F_w1.truncate(0) + F_w1.write(old2) + F_w1.close() + F_w1 = open(tempfilename_full, 'r') + F_w3 = open(controlfilename_full, 'w') + old = "" + count = 0 + line = F_w1.readline() + cnt = 0 + vce = 0.0 # Acc control effort + sce = 0.0 # Steering control effort + vce_accum = 0.0 # accumulated value for acc control effort + sce_accum = 0.0 # accumulated value for steering control effort + old = line[0:-2] + ',ceStr' + ',ceAcc' + ',teStr' + ',teU' # se is the steering error and ve is the acc error + while line: + line = F_w1.readline() + temp = line.split(',',11*16-1) + # print temp + old = old + '\n' + try: + for i in xrange(0,11): + old = old + temp[i*16] + ', ' + sce_accum = sce_accum + abs(float(temp[6 * 16])) + vce_accum = vce_accum + abs(float(temp[8 * 16])) + sce = vce_accum/(float(temp[0]) + 0.5) # Normalize the acc control effort by time + vce = sce_accum/(float(temp[0]) + 0.5) # Normalize the steering control effort by time + old = old + str(sce) + ' , ' # Concatenate the normalized acc control effort + old = old + str(vce) + ' , ' # Concatenate the normalized steering control effort + old = old + se[cnt] + ' , ' + old = old + ve[cnt] + + except: + pass + cnt += 1 + F_w3.truncate(0) + F_w3.write(old) + F_w1.close() + F_w3.close() + # Remove last several lines for control, because there are several redudant symbols + F_w3 = open(controlfilename_full, 'r') + lines = F_w3.readlines() + F_w3.close() + F_w3 = open(controlfilename_full, 'w') + F_w3.writelines([item for item in lines[:-3]]) + F_w3.close() + # Remove last several lines for planned, because there are several redudant symbols + F_w2 = open(plannedfilename_full, 'r') + lines = F_w2.readlines() + F_w2.close() + F_w2 = open(plannedfilename_full, 'w') + F_w2.writelines([item for item in lines[:-2]]) + F_w2.close() + os.remove(tempfilename_full) + os.remove(csvfilename_full) + + +# save sX.ymal +def readcase(demoname, casename, plannername, pathname): + configpath = "../ros/src/system/config/case/" + sxfile= configpath+casename+".yaml" + print("Reading "+casename+".yaml ...") + casefilename_full = os.path.join(pathname, "case.csv") + + F_sx = open(sxfile, 'r') + F_w = open(casefilename_full, 'w') + + line = F_sx.readline() + + name = "" + value = "" + while line: + line = str(line) + if len(line) > 1: + if line[1]!=' ': + line = line[1:-1] + line = line.split(":") + name1 = line[0] + elif line[2]!=' ': + line = line[2:] + line = line.split(":") + name2 = line[0] + if(name2[0] <= 'z' and name2[0] >= 'a'): + name2 = name2[0].upper()+name2[1:] + for char2 in name2: + if(char2 == '0'): + char2 = 'O' + if(len(line) > 1): + value2 = line[1] + value2 = value2[0:-1] + + + if(len(value2) > 0): + name = name + name1 + name2 + ',' + value = value + value2 + ',' + + elif line[3]!=' ': + line = line[3:] + line = line.split(": ") + name3 = line[0] + value3 = line[1] + + if(name3[0] <= 'z' and name3[0] >= 'a'): + name3 = name3[0].upper()+name3[1:] + for char3 in name3: + if(char3 == '0'): + char3 = 'O' + + name = name + name1 + name2 + name3 + ',' + value3 = value3.replace(",", " ") + value = value + value3[0:-1] + ',' + + + line = F_sx.readline() + value = name+'\n'+value + F_w.truncate(0) + #F_w.writelines(name) + F_w.write(value) + F_sx.close() + F_w.close() + print "Finished!" + + +if __name__ == '__main__': + # handle result information + print "Start to convert rosbag to csv: " + bag_name = sys.argv[1] + print("filename: "+bag_name) + tempname = str(sys.argv[1]).split("_") + demoname = tempname[0] + casename = tempname[1] + plannername = tempname[2] + print(demoname+" "+casename+" "+plannername) + + if len(sys.argv) == 2: + pathname = "test" + else: + pathname = str(sys.argv[2]) + + pathname = "./"+pathname+"/"+casename+plannername + print("save files to: " + pathname) + + # make dir + #dirname = os.path.dirname(filename) + if not os.path.exists(pathname): + os.makedirs(pathname) + + filename = bag2csv(bag_name) + processcsv(pathname, filename) + readcase(demoname, casename, plannername, pathname) + + diff --git a/ros/src/computing/mavs_msgs/CMakeLists.txt b/ros/src/computing/mavs_msgs/CMakeLists.txt index e25c12ef..eb400069 100644 --- a/ros/src/computing/mavs_msgs/CMakeLists.txt +++ b/ros/src/computing/mavs_msgs/CMakeLists.txt @@ -108,7 +108,7 @@ catkin_package( # INCLUDE_DIRS include # LIBRARIES mavs_msgs CATKIN_DEPENDS roscpp rospy std_msgs message_runtime - DEPENDS system_lib + # DEPENDS system_lib ) ########### @@ -117,10 +117,10 @@ catkin_package( ## Specify additional locations of header files ## Your package locations should be listed before other locations -include_directories( +#include_directories( # include - ${catkin_INCLUDE_DIRS} -) +# ${catkin_INCLUDE_DIRS} +#) ## Declare a C++ library # add_library(${PROJECT_NAME} diff --git a/ros/src/computing/perception/detection/obstacle_detection/launch/obstacle_detector.launch b/ros/src/computing/perception/detection/obstacle_detection/launch/main_pcl.launch similarity index 59% rename from ros/src/computing/perception/detection/obstacle_detection/launch/obstacle_detector.launch rename to ros/src/computing/perception/detection/obstacle_detection/launch/main_pcl.launch index 616a984a..aa3c0c96 100644 --- a/ros/src/computing/perception/detection/obstacle_detection/launch/obstacle_detector.launch +++ b/ros/src/computing/perception/detection/obstacle_detection/launch/main_pcl.launch @@ -1,10 +1,9 @@ - + - - + @@ -12,11 +11,9 @@ - - - + @@ -40,21 +37,6 @@ - - diff --git a/ros/src/computing/perception/detection/obstacle_detection/launch/main_scan.launch b/ros/src/computing/perception/detection/obstacle_detection/launch/main_scan.launch new file mode 100644 index 00000000..14a628b6 --- /dev/null +++ b/ros/src/computing/perception/detection/obstacle_detection/launch/main_scan.launch @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros/src/computing/perception/detection/obstacle_detection/resources/display.rviz b/ros/src/computing/perception/detection/obstacle_detection/resources/display.rviz index d072e87d..7bd0f9bb 100644 --- a/ros/src/computing/perception/detection/obstacle_detection/resources/display.rviz +++ b/ros/src/computing/perception/detection/obstacle_detection/resources/display.rviz @@ -7,9 +7,8 @@ Panels: - /Global Options1 - /Status1 - /Obstacles1 - - /PointCloud1 Splitter Ratio: 0.5 - Tree Height: 344 + Tree Height: 532 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -22,13 +21,14 @@ Panels: - Class: rviz/Views Expanded: - /Current View1 + - /Orbit1 Name: Views Splitter Ratio: 0.5 - Class: rviz/Time Experimental: false Name: Time SyncMode: 0 - SyncSource: "" + SyncSource: LaserScan Visualization Manager: Class: "" Displays: @@ -91,9 +91,15 @@ Visualization Manager: All Enabled: true base_footprint: Value: true + base_footprintObs: + Value: true base_link: Value: true - velodyne_top_link: + lidar_frame: + Value: true + map: + Value: true + odomObs: Value: true Marker Scale: 1 Name: TF @@ -101,7 +107,11 @@ Visualization Manager: Show Axes: true Show Names: true Tree: - {} + map: + base_footprint: + base_link: + lidar_frame: + {} Update Interval: 0 Value: true - Alpha: 1 @@ -134,6 +144,36 @@ Visualization Manager: Use Fixed Frame: true Use rainbow: false Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 0 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.00999999978 + Style: Flat Squares + Topic: /scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true Enabled: true Global Options: Background Color: 48; 48; 48 @@ -159,25 +199,25 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 128.532318 + Distance: 28.0431156 Enable Stereo Rendering: Stereo Eye Separation: 0.0599999987 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 201.703537 - Y: 54.0564156 - Z: 6.1973114 + X: -3.71715975 + Y: -3.33859897 + Z: -0.731496096 Focal Shape Fixed Size: false Focal Shape Size: 0.0500000007 Invert Z Axis: false Name: Current View Near Clip Distance: 0.00999999978 - Pitch: 1.36979651 - Target Frame: map + Pitch: 1.04039788 + Target Frame: base_link Value: Orbit (rviz) - Yaw: 4.73318672 + Yaw: 5.20539951 Saved: - Class: rviz/Orbit Distance: 429.459717 @@ -204,8 +244,8 @@ Window Geometry: collapsed: false Height: 846 Hide Left Dock: false - Hide Right Dock: false - QMainWindow State: 000000ff00000000fd00000004000000000000016a000002b6fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afc0000003a000002b6000000e001000019fa000000000100000002fb0000000a005600690065007700730100000000ffffffff0000010000fffffffb000000100044006900730070006c00610079007301000000000000016a0000015600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002c4fc0200000002fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005480000003efc0100000002fb0000000800540069006d00650100000000000005480000024400fffffffb0000000800540069006d00650100000000000004500000000000000000000003d8000002b600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd00000004000000000000016a000002b6fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afc0000003a000002b6000000e001000019fa000000010100000002fb0000000a005600690065007700730100000000ffffffff0000010000fffffffb000000100044006900730070006c00610079007301000000000000016a0000015600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002c4fc0200000002fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005480000003efc0100000002fb0000000800540069006d00650100000000000005480000024400fffffffb0000000800540069006d00650100000000000004500000000000000000000003d8000002b600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: diff --git a/ros/src/computing/perception/detection/obstacle_detection/src/obstacle_extractor.cpp b/ros/src/computing/perception/detection/obstacle_detection/src/obstacle_extractor.cpp index 4b6627e5..91660b30 100644 --- a/ros/src/computing/perception/detection/obstacle_detection/src/obstacle_extractor.cpp +++ b/ros/src/computing/perception/detection/obstacle_detection/src/obstacle_extractor.cpp @@ -98,10 +98,10 @@ bool ObstacleExtractor::updateParams(std_srvs::Empty::Request &req, std_srvs::Em nh_local_.param("/obstacle_detector/obstacle_extractor/max_circle_radius", p_max_circle_radius_, 0.6); nh_local_.param("/obstacle_detector/obstacle_extractor/radius_enlargement", p_radius_enlargement_, 0.25); - // nh_local_.param("min_x_limit", p_min_x_limit_, -10.0); - // nh_local_.param("max_x_limit", p_max_x_limit_, 10.0); - // nh_local_.param("min_y_limit", p_min_y_limit_, -10.0); - // nh_local_.param("max_y_limit", p_max_y_limit_, 10.0); + nh_local_.param("/obstacle_detector/obstacle_extractor/p_min_x_limit", p_min_x_limit_, -10.0); + nh_local_.param("/obstacle_detector/obstacle_extractor/p_max_x_limit", p_max_x_limit_, 10.0); + nh_local_.param("/obstacle_detector/obstacle_extractor/p_min_y_limit", p_min_y_limit_, -10.0); + nh_local_.param("/obstacle_detector/obstacle_extractor/p_max_y_limit", p_max_y_limit_, 10.0); nh_local_.param("/obstacle_detector/obstacle_extractor/frame_id", p_frame_id_, "map"); @@ -448,8 +448,8 @@ void ObstacleExtractor::publishObstacles() { } for (const Circle& c : circles_) { - //if (c.center.x > p_min_x_limit_ && c.center.x < p_max_x_limit_ && - // c.center.y > p_min_y_limit_ && c.center.y < p_max_y_limit_) { + if (c.center.x > p_min_x_limit_ && c.center.x < p_max_x_limit_ && + c.center.y > p_min_y_limit_ && c.center.y < p_max_y_limit_) { CircleObstacle circle; circle.center.x = c.center.x; @@ -460,7 +460,7 @@ void ObstacleExtractor::publishObstacles() { circle.true_radius = c.radius - p_radius_enlargement_; obstacles_msg->circles.push_back(circle); - //} + } } obstacles_pub_.publish(obstacles_msg); diff --git a/ros/src/computing/planning/motion/nloptcontrol_planner/CMakeLists.txt b/ros/src/computing/planning/motion/nloptcontrol_planner/CMakeLists.txt index ec51aba9..dee9ed10 100644 --- a/ros/src/computing/planning/motion/nloptcontrol_planner/CMakeLists.txt +++ b/ros/src/computing/planning/motion/nloptcontrol_planner/CMakeLists.txt @@ -24,4 +24,5 @@ catkin_python_setup() ## Generate added messages and services with any dependencies generate_messages(DEPENDENCIES std_msgs) + catkin_package() diff --git a/ros/src/computing/tools/visualization/data_plotter.py b/ros/src/computing/tools/visualization/data_plotter.py index 002274d0..c02d83b3 100755 --- a/ros/src/computing/tools/visualization/data_plotter.py +++ b/ros/src/computing/tools/visualization/data_plotter.py @@ -14,7 +14,7 @@ def __init__(self): self.t_actual = np.array([], dtype=np.float64) self.t_traj = np.array([], dtype=np.float64) self.t_traj_last = np.array([], dtype=np.float64) - + # position data self.x_actual = np.array([], dtype=np.float64) self.y_actual = np.array([], dtype=np.float64) @@ -91,10 +91,14 @@ def __init__(self): self.line_sa_actual = Line2D([], [], color='green', linewidth=2, linestyle='-') self.line_sa_traj = Line2D([], [], color='red', linewidth=1.5, linestyle='--') self.line_sa_traj_last = Line2D([], [], color='orange', linewidth=1.5, linestyle='--') + self.line_sa_upper_limit = Line2D([], [], color='black', linestyle='--') + self.line_sa_lower_limit = Line2D([], [], color='black', linestyle='--') self.sa_subplot.add_line(self.line_sa_actual) self.sa_subplot.add_line(self.line_sa_traj) self.sa_subplot.add_line(self.line_sa_traj_last) - self.sa_subplot.legend(['actual', 'planned', 'last planned'], fontsize='x-small') + self.sa_subplot.add_line(self.line_sa_upper_limit) + self.sa_subplot.add_line(self.line_sa_lower_limit) + self.sa_subplot.legend(['actual', 'planned', 'previous planned', 'upper limit', 'lower limit'], fontsize='x-small') self.sa_subplot.set_xlabel('time (s)', fontsize='larger', verticalalignment='center') self.sa_subplot.set_ylabel('sa (rad)', fontsize='larger') self.sa_subplot.tick_params('both', labelsize='x-small') @@ -119,10 +123,14 @@ def __init__(self): self.line_ax_actual = Line2D([], [], linewidth=1.8, color='green', linestyle='-') self.line_ax_traj = Line2D([], [], color='red', linewidth=1.5, linestyle='--') self.line_ax_traj_last = Line2D([], [], color='orange', linewidth=1.5, linestyle='--') + self.line_ax_upper_limit = Line2D([], [], color='black', linestyle='--') + self.line_ax_lower_limit = Line2D([], [], color='black', linestyle='--') self.ax_subplot.add_line(self.line_ax_actual) self.ax_subplot.add_line(self.line_ax_traj) self.ax_subplot.add_line(self.line_ax_traj_last) - self.ax_subplot.legend(['actual', 'planned', 'last planned'], fontsize='x-small') + self.ax_subplot.add_line(self.line_ax_upper_limit) + self.ax_subplot.add_line(self.line_ax_lower_limit) + self.ax_subplot.legend(['actual', 'planned', 'previous planned', 'upper limit', 'lower limit'], fontsize='x-small') self.ax_subplot.set_xlabel('time (s)', fontsize='larger', verticalalignment='center') self.ax_subplot.set_ylabel('ax (m/s)', fontsize='larger') self.ax_subplot.tick_params('both', labelsize='x-small') @@ -158,6 +166,8 @@ def draw_frame(self): self.line_sa_actual.set_data(self.t_actual, self.sa_actual) self.line_sa_traj.set_data(self.t_traj, self.sa_traj) self.line_sa_traj_last.set_data(self.t_traj_last, self.sa_traj_last) + self.line_sa_upper_limit.set_data(self.t_actual, self.sa_upper_limit) + self.line_sa_lower_limit.set_data(self.t_actual, self.sa_lower_limit) self.line_ux_actual.set_data(self.t_actual, self.ux_actual) self.line_ux_traj.set_data(self.t_traj, self.ux_traj) @@ -168,6 +178,8 @@ def draw_frame(self): self.line_ax_actual.set_data(self.t_actual, self.ax_actual) self.line_ax_traj.set_data(self.t_traj, self.ax_traj) self.line_ax_traj_last.set_data(self.t_traj_last, self.ax_traj_last) + self.line_ax_upper_limit.set_data(self.t_actual, self.ax_upper_limit) + self.line_ax_lower_limit.set_data(self.t_actual, self.ax_lower_limit) self.line_solve_time.set_data(self.solve_num, self.solve_time) self.line_solve_time_pass.set_data(self.solve_num_pass, self.solve_time_pass) @@ -179,11 +191,11 @@ def draw_frame(self): self.sa_subplot.set_xlim(self.t_actual[-1]-self.t_band, self.t_actual[-1]) self.ux_subplot.set_xlim(self.t_actual[-1]-self.t_band, self.t_actual[-1]) self.ax_subplot.set_xlim(self.t_actual[-1]-self.t_band, self.t_actual[-1]) - + if (len(self.solve_num) > 0 and self.solve_num[-1] > self.solve_num_band): self.tSolve_subplot.set_xlim(self.solve_num[0], self.solve_num[-1]) - + plt.draw() plt.pause(0.001) #0.001 except: @@ -198,6 +210,10 @@ def stateCallback(msg): data_plotter.ux_actual = np.append(data_plotter.ux_actual, msg.ux) data_plotter.sa_actual_real = np.append(data_plotter.sa_actual_real, msg.sa) data_plotter.ax_actual_real = np.append(data_plotter.ax_actual_real, msg.ax) + data_plotter.sa_upper_limit = np.append(data_plotter.sa_upper_limit, rospy.get_param('/vehicle/nloptcontrol_planner/sa_max')) + data_plotter.sa_lower_limit = np.append(data_plotter.sa_lower_limit, rospy.get_param('/vehicle/nloptcontrol_planner/sa_min')) + data_plotter.ax_upper_limit = np.append(data_plotter.ax_upper_limit, rospy.get_param('/vehicle/nloptcontrol_planner/ax_max')) + data_plotter.ax_lower_limit = np.append(data_plotter.ax_lower_limit, rospy.get_param('/vehicle/nloptcontrol_planner/ax_min')) if(len(data_plotter.ax_actual_real) > num_avg): data_plotter.ax_cumsum = data_plotter.ax_cumsum + data_plotter.ax_actual_real[(len(data_plotter.ax_actual_real)-1)]-data_plotter.ax_actual_real[(len(data_plotter.ax_actual_real)-num_avg-1)] @@ -207,8 +223,8 @@ def stateCallback(msg): data_plotter.ax_cumsum = data_plotter.ax_cumsum + data_plotter.ax_actual_real[len(data_plotter.ax_actual_real)-1] temp = data_plotter.ax_cumsum/len(data_plotter.ax_actual_real) data_plotter.ax_actual = np.append(data_plotter.ax_actual, temp) - - + + if(len(data_plotter.sa_actual_real) > num_avg): data_plotter.sa_cumsum = data_plotter.sa_cumsum + data_plotter.sa_actual_real[(len(data_plotter.sa_actual_real)-1)]-data_plotter.sa_actual_real[(len(data_plotter.sa_actual_real)-num_avg-1)] temp = sum(data_plotter.sa_actual_real[(len(data_plotter.sa_actual_real)-num_avg-1):(len(data_plotter.sa_actual_real)-1)])/num_avg @@ -217,17 +233,18 @@ def stateCallback(msg): data_plotter.sa_cumsum = data_plotter.sa_cumsum + data_plotter.sa_actual_real[len(data_plotter.sa_actual_real)-1] temp = data_plotter.sa_cumsum/len(data_plotter.sa_actual_real) data_plotter.sa_actual = np.append(data_plotter.sa_actual, temp) - + + def trajectoryCallback(msg): global data_plotter # # truncate the current message and append it to the old trajectory data_plotter.t_traj_last = np.append(data_plotter.t_traj_last, data_plotter.t_traj[1:2]) - data_plotter.x_traj_last = np.append(data_plotter.x_traj_last, data_plotter.x_traj[1:2]) + data_plotter.x_traj_last = np.append(data_plotter.x_traj_last, data_plotter.x_traj[1:2]) data_plotter.y_traj_last = np.append(data_plotter.y_traj_last, data_plotter.y_traj[1:2]) data_plotter.sa_traj_last = np.append(data_plotter.sa_traj_last, data_plotter.sa_traj[1:2]) - data_plotter.ux_traj_last = np.append(data_plotter.ux_traj_last, data_plotter.ux_traj[1:2]) + data_plotter.ux_traj_last = np.append(data_plotter.ux_traj_last, data_plotter.ux_traj[1:2]) data_plotter.ax_traj_last = np.append(data_plotter.ax_traj_last, data_plotter.ax_traj[1:2]) data_plotter.t_traj = msg.t @@ -256,7 +273,7 @@ def optCallback(msg): # initialize node rospy.init_node("visualization_plotter") - + # create a data plotter instance data_plotter = DataPlotter() @@ -265,11 +282,10 @@ def optCallback(msg): rospy.Subscriber("nlopcontrol_planner/control", Trajectory, trajectoryCallback) rospy.Subscriber("nlopcontrol_planner/opt", Optimization, optCallback) - rate = rospy.Rate(30) # 50hz + rate = rospy.Rate(50) # 50hz plt.ion() plt.show() while not rospy.is_shutdown(): data_plotter.draw_frame() rate.sleep() - diff --git a/ros/src/computing/tools/visualization/playback.launch b/ros/src/computing/tools/visualization/playback.launch index 2c10a9e9..51b11905 100644 --- a/ros/src/computing/tools/visualization/playback.launch +++ b/ros/src/computing/tools/visualization/playback.launch @@ -1,5 +1,9 @@ + + + + diff --git a/ros/src/models/chrono/README.md b/ros/src/models/chrono/README.md index e7ad1243..0bb48100 100644 --- a/ros/src/models/chrono/README.md +++ b/ros/src/models/chrono/README.md @@ -8,7 +8,6 @@ the initial desired path. The vehicle's states are published in a ROS msg and al - traj_gen_chrono - ros_chrono - - ros_chrono_msgs ## How to Build ``` diff --git a/ros/src/models/chrono/chrono_position_broadcaster/CMakeLists.txt b/ros/src/models/chrono/chrono_position_broadcaster/CMakeLists.txt index a60d2b80..158bbbeb 100644 --- a/ros/src/models/chrono/chrono_position_broadcaster/CMakeLists.txt +++ b/ros/src/models/chrono/chrono_position_broadcaster/CMakeLists.txt @@ -105,7 +105,6 @@ find_package(catkin REQUIRED COMPONENTS ## DEPENDS: system dependencies of this project that dependent projects also need catkin_package( # INCLUDE_DIRS include -# LIBRARIES ros_chrono_msgs CATKIN_DEPENDS roscpp rospy std_msgs # DEPENDS system_lib ) @@ -123,7 +122,6 @@ include_directories( ## Declare a C++ library # add_library(${PROJECT_NAME} -# src/${PROJECT_NAME}/ros_chrono_msgs.cpp # ) ## Add cmake target dependencies of the library @@ -134,7 +132,6 @@ include_directories( ## Declare a C++ executable ## With catkin_make all packages are built within a single CMake context ## The recommended prefix ensures that target names across packages don't collide -# add_executable(${PROJECT_NAME}_node src/ros_chrono_msgs_node.cpp) add_executable(chrono_position_broadcaster src/chrono_position_broadcaster.cpp) @@ -193,7 +190,6 @@ add_executable(chrono_position_broadcaster src/chrono_position_broadcaster.cpp) ############# ## Add gtest based cpp test target and link libraries -# catkin_add_gtest(${PROJECT_NAME}-test test/test_ros_chrono_msgs.cpp) # if(TARGET ${PROJECT_NAME}-test) # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) # endif() diff --git a/ros/src/models/chrono/ros_chrono/CMakeLists.txt b/ros/src/models/chrono/ros_chrono/CMakeLists.txt index 06f0a222..b3719bc1 100644 --- a/ros/src/models/chrono/ros_chrono/CMakeLists.txt +++ b/ros/src/models/chrono/ros_chrono/CMakeLists.txt @@ -15,7 +15,6 @@ find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs - ros_chrono_msgs mavs_msgs nloptcontrol_planner ) @@ -121,14 +120,15 @@ find_package(controller REQUIRED) catkin_package( # INCLUDE_DIRS include LIBRARIES ros_chrono - CATKIN_DEPENDS roscpp rospy std_msgs message_runtime ros_chrono_msgs mavs_msgs - DEPENDS system_lib Chrono interpolation controller + CATKIN_DEPENDS roscpp rospy std_msgs message_runtime mavs_msgs + DEPENDS interpolation controller ) ########### ## Build ## ########### + ## Specify additional locations of header files ## Your package locations should be listed before other locations #SET(Irrlicht_INCLUDE_DIRS "/home/shreyas/Downloads/irrlicht-1.8.4/include") diff --git a/ros/src/models/chrono/ros_chrono/old/hmmwv_model.cpp b/ros/src/models/chrono/ros_chrono/old/hmmwv_model.cpp deleted file mode 100644 index f9d1cb4f..00000000 --- a/ros/src/models/chrono/ros_chrono/old/hmmwv_model.cpp +++ /dev/null @@ -1,1002 +0,0 @@ -// ============================================================================= -// PROJECT CHRONO - http://projectchrono.org -// -// Copyright (c) 2014 projectchrono.org -// All rights reserved. -// -// Use of this source code is governed by a BSD-style license that can be found -// in the LICENSE file at the top level of the distribution and at -// http://projectchrono.org/license-chrono.txt. -// -// ============================================================================= -// Authors: Radu Serban -// ============================================================================= -// -// Demonstration of a steering path-follower PID controller. -// -// ============================================================================= - -#include -#include -#include "boost/bind.hpp" -#include "chrono/core/ChFileutils.h" -#include "chrono/core/ChRealtimeStep.h" -#include "chrono/utils/ChFilters.h" -#include -#include -#include "ros/ros.h" -#include "std_msgs/String.h" -#include "ros_chrono_msgs/veh_status.h" -#include - -//#include "tf/tf.h" -#include -#include "chrono_vehicle/ChVehicleModelData.h" -#include "chrono_vehicle/terrain/RigidTerrain.h" -#include "chrono_vehicle/driver/ChIrrGuiDriver.h" -#include "chrono_vehicle/driver/ChPathFollowerDriver.h" -#include "chrono_vehicle/wheeled_vehicle/utils/ChWheeledVehicleIrrApp.h" -#include -#include "chrono_models/vehicle/hmmwv/HMMWV.h" -#include "chrono/physics/ChSystem.h" -#include "chrono_vehicle/wheeled_vehicle/tire/ChPacejkaTire.h" -//#include "chrono_models/vehicle/hmmwv/HMMWV_Pac02Tire.h" -#include "chrono_vehicle/wheeled_vehicle/tire/RigidTire.h" -#include "chrono_vehicle/wheeled_vehicle/tire/LugreTire.h" -#include "chrono_models/vehicle/hmmwv/HMMWV_ReissnerTire.h" -#include "chrono_vehicle/ChSubsysDefs.h" -#include "chrono_vehicle/wheeled_vehicle/vehicle/WheeledVehicle.h" -#include "chrono_vehicle/powertrain/ChShaftsPowertrain.h" -#include "chrono_vehicle/powertrain/SimplePowertrain.h" - -#include - -#include "chrono/core/ChFileutils.h" -#include "chrono/core/ChStream.h" -#include "chrono/utils/ChFilters.h" -#include "chrono/utils/ChUtilsInputOutput.h" -#include "chrono/solver/ChSolverMINRES.h" - -#include "chrono_vehicle/ChConfigVehicle.h" - -#define PI 3.1415926535 -//using veh_status.msg -using namespace chrono; -using namespace chrono::geometry; -using namespace chrono::vehicle; -using namespace chrono::vehicle::hmmwv; - - -// ============================================================================= -// Problem parameters -// Main Data Path -//std::string data_path("/home/shreyas/.julia/v0.6/MAVs/catkin_ws/data/vehicle/"); -std::string data_path("../../../src/models/chrono/ros_chrono/src/data/vehicle/"); -//std::string data_path("src/system/chrono/ros_chrono/src/data/vehicle/"); -// Contact method type -ChMaterialSurface::ContactMethod contact_method = ChMaterialSurface::NSC; - -// Type of tire model (RIGID, LUGRE, FIALA, or PACEJKA) -//TireModelType tire_model = TireModelType::RIGID; - -// Input file name for PACEJKA tires if they are selected -std::string pacejka_tire_file_left(data_path+"hmmwv/tire/HMMWV_pacejka_left.tir"); -std::string pacejka_tire_file_right(data_path+"hmmwv/tire/HMMWV_pacejka_right.tir"); -std::string lugre_tire_file(data_path+"hmmwv/tire/HMMWV_LugreTire.json"); -std::string rigid_tire_file(data_path+"hmmwv/tire/HMMWV_RigidTire.json"); -std::string reissner_tire_file(data_path+"hmmwv/tire/HMMWV_ReissnerTire.json"); - -//std::string pacejka_tire_file(data_path+"hmmwv/tire/HMMWV_RigidTire.json"); - -//std::string pacejka_tire_file("hmmwv/tire/HMMWV_pacejka.tir"); -// Type of powertrain model (SHAFTS or SIMPLE) -PowertrainModelType powertrain_model = PowertrainModelType::SHAFTS; - -// Drive type (FWD, RWD, or AWD) -DrivelineType drive_type = DrivelineType::RWD; - -// Visualization type for vehicle parts (PRIMITIVES, MESH, or NONE) -VisualizationType chassis_vis_type = VisualizationType::PRIMITIVES; -VisualizationType suspension_vis_type = VisualizationType::PRIMITIVES; -VisualizationType steering_vis_type = VisualizationType::PRIMITIVES; -VisualizationType wheel_vis_type = VisualizationType::NONE; -VisualizationType tire_vis_type = VisualizationType::PRIMITIVES; - -// Input file names for the path-follower driver model -std::string steering_controller_file(data_path+"generic/driver/SteeringController.json"); -//std::string steering_controller_file("generic/driver/SteeringController.json"); -std::string speed_controller_file(data_path+"generic/driver/SpeedController.json"); -//std::string speed_controller_file("generic/driver/SpeedController.json"); -// std::string path_file("paths/straight.txt"); -std::string path_file(data_path+"paths/my_path.txt"); -std::string simplepowertrain_file(data_path+"hmmwv/powertrain/HMMWV_ShaftsPowertrain.json"); -WheelState wheel_states[4]; - -// Rigid terrain dimensions -double terrainHeight = 0; -double terrainLength = 500.0; // size in X direction -double terrainWidth = 500.0; // size in Y direction - -// Point on chassis tracked by the chase camera -ChVector<> trackPoint(0.0, 0.0, 1.75); - -// Simulation step size -double step_size = 1e-2; -double tire_step_size = step_size; - -// Simulation end time -double t_end = 1000; - -// Render FPS -double fps = 60; - -// Debug logging -bool debug_output = false; -double debug_fps = 10; - -// Output directories -const std::string out_dir = GetChronoOutputPath() + "STEERING_CONTROLLER"; -const std::string pov_dir = out_dir + "/POVRAY"; - -// POV-Ray output -bool povray_output = false; - -// Vehicle state output (forced to true if povray output enabled) -bool state_output = false; -int filter_window_size = 20; - - -// ============================================================================= - - -// Custom Irrlicht event receiver for selecting current driver model. -class ChDriverSelector : public irr::IEventReceiver { - public: - ChDriverSelector(const ChVehicle& vehicle, ChPathFollowerDriver* driver_follower, ChIrrGuiDriver* driver_gui) - : m_vehicle(vehicle), - m_driver_follower(driver_follower), - m_driver_gui(driver_gui), - m_driver(m_driver_follower), - m_using_gui(false) {} - - ChDriver* GetDriver() { return m_driver; } - ChPathFollowerDriver* GetPathFollower() { return m_driver_follower; } - - bool UsingGUI() const { return m_using_gui; } - - void update_driver(ChPathFollowerDriver* driver_follower){ - m_driver_follower = driver_follower; - m_driver = m_driver_follower; - } - - virtual bool OnEvent(const irr::SEvent& event) { - return false; - } - - private: - bool m_using_gui; - const ChVehicle& m_vehicle; - ChPathFollowerDriver* m_driver_follower; - ChIrrGuiDriver* m_driver_gui; - ChDriver* m_driver; -}; - -struct parameters -{ - RigidTerrain terrain; - TireForces tire_forces; - WheeledVehicle my_hmmwv; - ChRealtimeStepTimer realtime_timer; - int sim_frame; - double steering_input; - double throttle_input; - double braking_input; - irr::scene::IMeshSceneNode* ballS; - irr::scene::IMeshSceneNode* ballT; - std::vector x_traj_curr; - std::vector y_traj_curr; - std::vector x_traj_prev; - std::vector y_traj_prev; - double target_speed; - int render_steps; - int render_frame; -} ; - -void waitForLoaded(ros::NodeHandle &n){ - bool planner_init = false; - std::string planner_namespace; - n.getParam("system/planner",planner_namespace); - n.getParam("system/"+planner_namespace+"/flags/initialized",planner_init); - while(!planner_init){ - usleep(500); // < my question - n.getParam("system/"+planner_namespace+"/flags/initialized",planner_init); - - } - usleep(500); //sleep another 500ms to ensure everything is loaded. - //continue on here -} - -void write_path(parameters &hmmwv_params, std::string path_file){ - double num_pts = hmmwv_params.x_traj_curr.size(); - double num_cols = 3; - double z_val = 0.5; - std::ofstream myfile; - myfile.open(path_file,std::ofstream::out | std::ofstream::trunc); - - myfile << ' ' << num_pts << ' '<< num_cols << '\n'; - - for (int pt_cnt=0; pt_cnt= 3*PI/2) yaw0 = -yaw0 + 5*PI/2; - // else yaw0 = -yaw0 + PI/2; - // yaw0 = -yaw0 + PI; - setSteeringParams(n); - setDrivelineParams(n); - setBrakingParams(n); - setChassisParams(n); - ChVector<> initLoc(x0, y0, z0); -// ChQuaternion<> initRot(q[0],q[1],q[2],q[3]); - - double t0 = std::cos(yaw0 * 0.5f); - double t1 = std::sin(yaw0 * 0.5f); - double t2 = std::cos(roll0 * 0.5f); - double t3 = std::sin(roll0 * 0.5f); - double t4 = std::cos(pitch0 * 0.5f); - double t5 = std::sin(pitch0 * 0.5f); - - double q0_0 = t0 * t2 * t4 + t1 * t3 * t5; - double q0_1 = t0 * t3 * t4 - t1 * t2 * t5; - double q0_2 = t0 * t2 * t5 + t1 * t3 * t4; - double q0_3 = t1 * t2 * t4 - t0 * t3 * t5; - - ChQuaternion<> initRot(q0_0,q0_1,q0_2,q0_3); - //ChQuaternion<> initRot(cos(PI/4), 0, 0, sin(PI/4)); //initial yaw of pi/2 - - ros::Publisher vehicleinfo_pub = n.advertise("vehicleinfo", 1); - - //ros::Rate loop_rate(5); - - // ------------------------------ - // Create the vehicle and terrain - // ------------------------------ - - // Create the HMMWV vehicle, set parameters, and initialize - // HMMWV_Reduced my_hmmwv; - std::cout << "Start reading the file" << std::endl; - WheeledVehicle my_hmmwv(data_path + "hmmwv/vehicle/HMMWV_Vehicle.json",contact_method); - my_hmmwv.Initialize(ChCoordsys<>(initLoc, initRot),0.0); - - std::cout << "Successfully read the file" << std::endl; - my_hmmwv.SetChassisVehicleCollide(false); - my_hmmwv.GetChassis()->SetVisualizationType(chassis_vis_type); -// my_hmmwv.GetChassis()->AddVisualizationAssets(chassis_vis_type); - - my_hmmwv.SetSuspensionVisualizationType(suspension_vis_type); - my_hmmwv.SetSteeringVisualizationType(steering_vis_type); - my_hmmwv.SetWheelVisualizationType(wheel_vis_type); - //my_hmmwv.SetTireVisualizationType(tire_vis_type); - RigidTire tire_front_left(rigid_tire_file); - RigidTire tire_front_right(rigid_tire_file); - RigidTire tire_rear_left(rigid_tire_file); - RigidTire tire_rear_right(rigid_tire_file); - - - TireForces tire_forces(4); - - tire_front_left.Initialize(my_hmmwv.GetWheelBody(0), LEFT); - tire_front_right.Initialize(my_hmmwv.GetWheelBody(1), LEFT); - tire_rear_left.Initialize(my_hmmwv.GetWheelBody(2), RIGHT); - tire_rear_right.Initialize(my_hmmwv.GetWheelBody(3), RIGHT); - - - tire_front_left.SetVisualizationType(tire_vis_type); - tire_front_right.SetVisualizationType(tire_vis_type); - tire_rear_left.SetVisualizationType(tire_vis_type); - tire_rear_right.SetVisualizationType(tire_vis_type); - /* wheel_states[0] = my_hmmwv.GetWheelState(0); - wheel_states[1] = my_hmmwv.GetWheelState(1); - wheel_states[2] = my_hmmwv.GetWheelState(2); - wheel_states[3] = my_hmmwv.GetWheelState(3); - - - tire_forces[0] = tire_front_left.GetTireForce(); - tire_forces[1] = tire_front_right.GetTireForce(); - tire_forces[2] = tire_rear_left.GetTireForce(); - tire_forces[3] = tire_rear_right.GetTireForce();*/ - - // Create the terrain - float frict_coeff, rest_coeff; - n.getParam("vehicle/common/frict_coeff",frict_coeff); - n.getParam("vehicle/common/rest_coeff",rest_coeff); - - RigidTerrain terrain(my_hmmwv.GetSystem()); - my_hmmwv.GetWheel(0)->SetContactFrictionCoefficient(frict_coeff); - my_hmmwv.GetWheel(0)->SetContactRestitutionCoefficient(rest_coeff); - - //terrain.SetContactFrictionCoefficient(0.9f); - //terrain.SetContactRestitutionCoefficient(0.01f); - terrain.SetContactMaterialProperties(2e7f, 0.3f); - terrain.SetColor(ChColor(1, 1, 1)); - //terrain.SetTexture(chrono::vehicle::GetDataFile("terrain/textures/tile4.jpg"), 200, 200); - terrain.SetTexture(data_path+"terrain/textures/tile4.jpg", 200, 200); - terrain.Initialize(terrainHeight, terrainLength, terrainWidth); - - //SimplePowertrain powertrain(vehicle::GetDataFile("hmmwv/powertrain/HMMWV_SimplePowertrain.json")); - HMMWV_Powertrain powertrain; - powertrain.Initialize(my_hmmwv.GetChassisBody(),my_hmmwv.GetDriveshaft()); - std::vector GearRatios; - n.getParam("vehicle/chrono/vehicle_params/gearRatios",GearRatios); - powertrain.SetGearRatios(GearRatios); - // --------------------------------------- - // Create the vehicle Irrlicht application - // --------------------------------------- - - ChVehicleIrrApp app(&my_hmmwv, &powertrain, L"Steering Controller Demo", - irr::core::dimension2d(800, 640)); - - app.SetHUDLocation(500, 20); - app.SetSkyBox(); - app.AddTypicalLogo(); - app.AddTypicalLights(irr::core::vector3df(-150.f, -150.f, 200.f), irr::core::vector3df(-150.f, 150.f, 200.f), 100, - 100); - app.AddTypicalLights(irr::core::vector3df(150.f, -150.f, 200.f), irr::core::vector3df(150.0f, 150.f, 200.f), 100, - 100); - app.EnableGrid(false); - app.SetChaseCamera(trackPoint, 6.0, 0.5); - - app.SetTimestep(step_size); - app.SetTryRealtime(true); - - // Visualization of controller points (sentinel & target) - irr::scene::IMeshSceneNode* ballS = app.GetSceneManager()->addSphereSceneNode(0.1f); - irr::scene::IMeshSceneNode* ballT = app.GetSceneManager()->addSphereSceneNode(0.1f); - ballS->getMaterial(0).EmissiveColor = irr::video::SColor(0, 255, 0, 0); - ballT->getMaterial(0).EmissiveColor = irr::video::SColor(0, 0, 255, 0); - - // ------------------------- - // Create the driver systems - // ------------------------- - - // Create both a GUI driver and a path-follower and allow switching between them - ChIrrGuiDriver driver_gui(app); - driver_gui.Initialize(); - - /* - ChPathFollowerDriver driver_follower(my_hmmwv.GetVehicle(), path, "my_path", target_speed); - driver_follower.GetSteeringController().SetLookAheadDistance(5); - driver_follower.GetSteeringController().SetGains(0.5, 0, 0); - driver_follower.GetSpeedController().SetGains(0.4, 0, 0); - */ - - // --------------- - // Simulation loop - // --------------- - - // Driver location in vehicle local frame - ChVector<> driver_pos = my_hmmwv.GetChassis()->GetLocalDriverCoordsys().pos; - // Number of simulation steps between miscellaneous events - double render_step_size = 1 / fps; - int render_steps = (int)std::ceil(render_step_size / step_size); - double debug_step_size = 1 / debug_fps; - int debug_steps = (int)std::ceil(debug_step_size / step_size); - - // Initialize simulation frame counter and simulation time - ChRealtimeStepTimer realtime_timer; - int sim_frame = 0; - int render_frame = 0; - - double throttle_input, steering_input, braking_input; - std::vector x_traj_curr, y_traj_curr,x_traj_prev,y_traj_prev; //Initialize xy trajectory vectors - parameters hmmwv_params{terrain,tire_forces,my_hmmwv,realtime_timer,sim_frame,steering_input,throttle_input,braking_input,ballS,ballT,x_traj_curr,y_traj_curr,x_traj_prev,y_traj_prev,target_speed,render_steps,render_frame}; - //Load xy parameters for the first timestep - // std::string planner_namespace; - // n.getParam("system/planner",planner_namespace); - n.getParam(planner_namespace +"/traj/x",hmmwv_params.x_traj_curr); - n.getParam(planner_namespace + "/traj/yVal",hmmwv_params.y_traj_curr); - hmmwv_params.x_traj_prev=hmmwv_params.x_traj_curr; - hmmwv_params.y_traj_prev=hmmwv_params.y_traj_curr; - - write_path(hmmwv_params, path_file); - // ---------------------- - // Create the Bezier path - // ---------------------- - - auto path = ChBezierCurve::read(path_file); - - ChPathFollowerDriver* driver_follower_p = new ChPathFollowerDriver(hmmwv_params.my_hmmwv, steering_controller_file, - speed_controller_file, path, "my_path", hmmwv_params.target_speed); - - driver_follower_p->Initialize(); - - - // Create and register a custom Irrlicht event receiver to allow selecting the - // current driver model. - ChDriverSelector selector(my_hmmwv, driver_follower_p, &driver_gui); - app.SetUserEventReceiver(&selector); - - // Finalize construction of visualization assets - app.AssetBindAll(); - app.AssetUpdateAll(); - - // ----------------- - // Initialize output - // ----------------- - - state_output = state_output || povray_output; - - if (state_output) { - if (ChFileutils::MakeDirectory(out_dir.c_str()) < 0) { - std::cout << "Error creating directory " << out_dir << std::endl; - return 1; - } - } - - if (povray_output) { - if (ChFileutils::MakeDirectory(pov_dir.c_str()) < 0) { - std::cout << "Error creating directory " << pov_dir << std::endl; - return 1; - } - driver_follower_p->ExportPathPovray(out_dir); - } -/* - utils::CSV_writer csv("\t"); - csv.stream().setf(std::ios::scientific | std::ios::showpos); - csv.stream().precision(6); -*/ - utils::ChRunningAverage fwd_acc_GC_filter(filter_window_size); - utils::ChRunningAverage lat_acc_GC_filter(filter_window_size); - - utils::ChRunningAverage fwd_acc_driver_filter(filter_window_size); - utils::ChRunningAverage lat_acc_driver_filter(filter_window_size); - - std::ofstream myfile1; - myfile1.open(data_path+"paths/position.txt",std::ofstream::out | std::ofstream::trunc); - //get mass and moment of inertia about z axis - n.setParam("vehicle/common/m",my_hmmwv.GetVehicleMass()); - const ChMatrix33<> inertia_mtx= my_hmmwv.GetChassisBody()->GetInertia(); - double Izz=inertia_mtx.GetElement(2,2); - n.setParam("vehicle/common/Izz",Izz); - // get distance to front and rear axles - // enum chrono::vehicle::VehicleSide LEFT; - // enum chrono::vehicle::VehicleSide RIGHT; - ChVector<> veh_com= my_hmmwv.GetVehicleCOMPos(); - ChVector<> la_pos=my_hmmwv.GetSuspension(0)->GetSpindlePos(chrono::vehicle::VehicleSide::RIGHT); - ChVector<> lb_pos=my_hmmwv.GetSuspension(0)->GetSpindlePos(chrono::vehicle::VehicleSide::LEFT); - double la_length, lb_length; - ChVector<> la_diff; - la_diff.Sub(veh_com,la_pos); - ChVector<> lb_diff; - lb_diff.Sub(veh_com,lb_pos); - la_length=la_diff.Length(); - lb_length=lb_diff.Length(); - n.setParam("vehicle/common/la",la_length); - n.setParam("vehicle/common/lb",lb_length); - - // get friction and restitution coefficients - // float frict_coeff, rest_coeff; - frict_coeff = my_hmmwv.GetWheel(0)->GetCoefficientFriction(); - rest_coeff = my_hmmwv.GetWheel(0)->GetCoefficientRestitution(); - n.setParam("vehicle/common/frict_coeff",frict_coeff); - n.setParam("vehicle/common/rest_coeff",rest_coeff); - - while(n.ok()){ - while (running) { - if(gui_switch) app.GetDevice()->run(); - n.setParam("system/chrono/flags/running",true); - double time = hmmwv_params.my_hmmwv.GetSystem()->GetChTime(); - // Get trajectory parameters again - n.getParam("system/"+planner_namespace+"/flags/initialized",planner_init); - if (planner_init){ - n.getParam("system/planner",planner_namespace); - n.getParam(planner_namespace+"/traj/x",hmmwv_params.x_traj_curr); - n.getParam(planner_namespace+"/traj/yVal",hmmwv_params.y_traj_curr); - - double num_pts = hmmwv_params.x_traj_curr.size(); - - if (hmmwv_params.x_traj_curr!=hmmwv_params.x_traj_prev || hmmwv_params.y_traj_curr != hmmwv_params.y_traj_prev){ - write_path(hmmwv_params, path_file); - auto path = ChBezierCurve::read(path_file); - delete driver_follower_p; - driver_follower_p = new ChPathFollowerDriver(my_hmmwv, steering_controller_file, - speed_controller_file, path, "my_path_", target_speed); - driver_follower_p->Initialize(); - selector.update_driver(driver_follower_p); - if(gui_switch) app.SetUserEventReceiver(&selector); - app.AssetBindAll(); - app.AssetUpdateAll(); - app.GetDevice()->run(); - - hmmwv_params.x_traj_prev=hmmwv_params.x_traj_curr; - hmmwv_params.y_traj_prev=hmmwv_params.y_traj_curr; - } - } - - /* - // Hack for acceleration-braking maneuver - static bool braking = false; - if (my_hmmwv.GetVehicle().GetVehicleSpeed() > target_speed) - braking = true; - if (braking) { - throttle_input = 0; - braking_input = 1; - } else { - throttle_input = 1; - braking_input = 0; - } - */ - - // ros::Subscriber sub = n.subscribe("desired_ref", 1, ¶meters::controlCallback, &hmmwv_params); - - // Render scene and output POV-Ray data - if (hmmwv_params.sim_frame % hmmwv_params.render_steps == 0 && gui_switch) { - - app.BeginScene(true, true, irr::video::SColor(255, 140, 161, 192)); - app.DrawAll(); - app.EndScene(); - - - hmmwv_params.render_frame++; - } - /* - // Debug logging - if (debug_output && sim_frame % debug_steps == 0) { - GetLog() << "driver acceleration: " << acc_driver.x() << " " << acc_driver.y() << " " << acc_driver.z() - << "\n"; - GetLog() << "CG acceleration: " << acc_CG.x() << " " << acc_CG.y() << " " << acc_CG.z() << "\n"; - GetLog() << "\n"; - }*/ - - ros_chrono_msgs::veh_status data_out; - /* - ChVector<> acc_CG = my_hmmwv.GetVehicle().GetChassisBody()->GetPos_dtdt(); - ChVector<> acc_driver = my_hmmwv.GetVehicle().GetVehicleAcceleration(driver_pos); - double fwd_acc_CG = fwd_acc_GC_filter.Add(acc_CG.x()); - double lat_acc_CG = lat_acc_GC_filter.Add(acc_CG.y()); - double fwd_acc_driver = fwd_acc_driver_filter.Add(acc_driver.x()); - double lat_acc_driver = lat_acc_driver_filter.Add(acc_driver.y());*/ - - // End simulation - if (time >= t_end) - break; - - const ChVector<> pS = selector.GetPathFollower()->GetSteeringController().GetSentinelLocation(); - const ChVector<> pT = selector.GetPathFollower()->GetSteeringController().GetTargetLocation(); - hmmwv_params.ballS->setPosition(irr::core::vector3df((irr::f32)pS.x(), (irr::f32)pS.y(), (irr::f32)pS.z())); - hmmwv_params.ballT->setPosition(irr::core::vector3df((irr::f32)pT.x(), (irr::f32)pT.y(), (irr::f32)pT.z())); - - time = hmmwv_params.my_hmmwv.GetSystem()->GetChTime(); - hmmwv_params.throttle_input = selector.GetDriver()->GetThrottle(); - hmmwv_params.steering_input = selector.GetDriver()->GetSteering(); - hmmwv_params.braking_input = selector.GetDriver()->GetBraking(); - // Update modules (process inputs from other modules) - hmmwv_params.tire_forces[0] = tire_front_left.GetTireForce(); - hmmwv_params.tire_forces[1] = tire_front_right.GetTireForce(); - hmmwv_params.tire_forces[2] = tire_rear_left.GetTireForce(); - hmmwv_params.tire_forces[3] = tire_rear_right.GetTireForce(); - - wheel_states[0] = hmmwv_params.my_hmmwv.GetWheelState(0); - wheel_states[1] = hmmwv_params.my_hmmwv.GetWheelState(1); - wheel_states[2] = hmmwv_params.my_hmmwv.GetWheelState(2); - wheel_states[3] = hmmwv_params.my_hmmwv.GetWheelState(3); - - double x, y, goal_tol; - n.getParam("state/chrono/x",x); - n.getParam("state/chrono/yVal",y); - n.getParam("system/params/goal_tol",goal_tol); - double distance = sqrt( (goal_x-x)*(goal_x-x) + (goal_y-y)*(goal_y-y) ); - if(distance < goal_tol){ - goal_attained = true; - n.setParam("system/flags/goal_attained","true"); - // n.setParam("system/chrono/flags/running","false"); - running = false; - hmmwv_params.braking_input = 1.0; - hmmwv_params.throttle_input = 0.0; - std::cout << "Goal attained!" << std::endl; - } - selector.GetPathFollower()->Synchronize(time); - driver_gui.Synchronize(time); - hmmwv_params.terrain.Synchronize(time); - // hmmwv_params.my_hmmwv.Synchronize(time, hmmwv_params.steering_input, hmmwv_params.braking_input, hmmwv_params.throttle_input, hmmwv_params.terrain); - tire_front_left.Synchronize(time, wheel_states[0], hmmwv_params.terrain); - tire_front_right.Synchronize(time, wheel_states[1], hmmwv_params.terrain); - tire_rear_left.Synchronize(time, wheel_states[2], hmmwv_params.terrain); - tire_rear_right.Synchronize(time, wheel_states[3], hmmwv_params.terrain); - - double powertrain_torque=powertrain.GetOutputTorque(); - double driveshaft_speed=my_hmmwv.GetDriveshaftSpeed(); - powertrain.Synchronize(time,hmmwv_params.throttle_input,driveshaft_speed); - - hmmwv_params.my_hmmwv.Synchronize(time, hmmwv_params.steering_input, hmmwv_params.braking_input, powertrain_torque, hmmwv_params.tire_forces); - - std::string msg = selector.UsingGUI() ? "GUI driver" : "Follower driver"; - if(gui_switch) app.Synchronize(msg, hmmwv_params.steering_input, hmmwv_params.throttle_input, hmmwv_params.braking_input); - // Advance simulation for one timestep for all modules - double step = hmmwv_params.realtime_timer.SuggestSimulationStep(step_size); - selector.GetPathFollower()->Advance(step); - driver_gui.Advance(step); - powertrain.Advance(step); - hmmwv_params.my_hmmwv.Advance(step); - hmmwv_params.terrain.Advance(step); - tire_front_right.Advance(tire_step_size); - tire_front_left.Advance(tire_step_size); - tire_rear_right.Advance(tire_step_size); - tire_rear_left.Advance(tire_step_size); - if(gui_switch) app.Advance(step); - - // Increment simulation frame number - hmmwv_params.sim_frame++; - - ChVector<> global_pos = hmmwv_params.my_hmmwv.GetVehicleCOMPos();//global location of chassis reference frame origin - ChQuaternion<> global_orntn = hmmwv_params.my_hmmwv.GetVehicleRot();//global orientation as quaternion - ChVector<> rot_dt = hmmwv_params.my_hmmwv.GetChassisBody()->GetWvel_loc();//global orientation as quaternion - ChVector<> global_velCOM = hmmwv_params.my_hmmwv.GetChassisBody()->GetPos_dt(); - ChVector<> global_accCOM = hmmwv_params.my_hmmwv.GetChassisBody()->GetPos_dtdt(); - //ChVector<> euler_ang = global_orntn.Q_to_Rotv(); //convert to euler angles - //ChPacejkaTire<> slip_angle = GetSlipAngle() - double slip_angle = tire_front_left.GetLongitudinalSlip(); - - double q0 = global_orntn[0]; - double q1 = global_orntn[1]; - double q2 = global_orntn[2]; - double q3 = global_orntn[3]; - - double yaw_val=atan2(2*(q0*q3+q1*q2),1-2*(q2*q2+q3*q3)); - double theta_val=asin(2*(q0*q2-q3*q1)); - double phi_val= atan2(2*(q0*q1+q2*q3),1-2*(q1*q1+q2*q2)); - - n.setParam("state/chrono/t",time); //time in chrono simulation - n.setParam("state/chrono/x", global_pos[0]) ; - n.setParam("state/chrono/yVal",global_pos[1]); - n.setParam("state/chrono/ux",fabs(global_velCOM[0])); //speed measured at the origin of the chassis reference frame. - n.setParam("state/chrono/v", global_velCOM[1]); - n.setParam("state/chrono/ax", global_accCOM[0]); - n.setParam("state/chrono/psi",yaw_val); //in radians - n.setParam("state/chrono/theta",theta_val); //in radians - n.setParam("state/chrono/phi",phi_val); //in radians - n.setParam("state/chrono/r",-rot_dt[2]);//yaw rate - n.setParam("state/chrono/sa",slip_angle); //slip angle - n.setParam("state/chrono/control/thr",hmmwv_params.throttle_input); //throttle input in the range [0,+1] - n.setParam("state/chrono/control/brk",hmmwv_params.braking_input); //braking input in the range [0,+1] - n.setParam("state/chrono/control/str",hmmwv_params.steering_input); //steeering input in the range [-1,+1] - - - data_out.t_chrono=time; //time in chrono simulation - data_out.x_pos= global_pos[0]; - data_out.y_pos=global_pos[1]; - data_out.x_v= fabs(global_velCOM[0]); //speed measured at the origin of the chassis reference frame. - data_out.y_v= global_velCOM[1]; - data_out.x_a= global_accCOM[0]; - data_out.yaw_curr=yaw_val; //in radians - data_out.yaw_rate=-rot_dt[2];//yaw rate - data_out.sa=slip_angle; //slip angle - data_out.thrt_in=hmmwv_params.throttle_input; //throttle input in the range [0,+1] - data_out.brk_in=hmmwv_params.braking_input; //braking input in the range [0,+1] - data_out.str_in=hmmwv_params.steering_input; //steeering input in the range [-1,+1] - - vehicleinfo_pub.publish(data_out); - // loop_rate.sleep(); - - myfile1 << ' ' << global_pos[0] << ' '<< global_pos[1] <<' ' << global_pos[2] << '\n'; - - } -/* - if (state_output){ - csv.write_to_file(out_dir + "/state.out"); - }*/ - myfile1.close(); - //ros::shutdown(); - } - return 0; -} diff --git a/ros/src/models/chrono/ros_chrono/old/hmmwv_model_callback.cpp b/ros/src/models/chrono/ros_chrono/old/hmmwv_model_callback.cpp deleted file mode 100644 index 1899bcce..00000000 --- a/ros/src/models/chrono/ros_chrono/old/hmmwv_model_callback.cpp +++ /dev/null @@ -1,730 +0,0 @@ -// ============================================================================= -// PROJECT CHRONO - http://projectchrono.org -// -// Copyright (c) 2014 projectchrono.org -// All rights reserved. -// -// Use of this source code is governed by a BSD-style license that can be found -// in the LICENSE file at the top level of the distribution and at -// http://projectchrono.org/license-chrono.txt. -// -// ============================================================================= -// Authors: Radu Serban -// ============================================================================= -// -// Demonstration of a steering path-follower PID controller. -// -// The vehicle reference frame has Z up, X towards the front of the vehicle, and -// Y pointing to the left. -// TO DO: -// Find proper yaw rate calculation -// Subsscribe to msg from obstacle_avoidance_chrono, callback to that to calculate ChBezierCurve -// ============================================================================= - -#include -#include -#include "boost/bind.hpp" -#include "chrono/core/ChFileutils.h" -#include "chrono/core/ChRealtimeStep.h" -#include "chrono/utils/ChFilters.h" -#include -#include -#include "ros/ros.h" -#include "std_msgs/String.h" -#include "ros_chrono_msgs/veh_status.h" -#include "traj_gen_chrono/Trajectory.h" -#include -#include "chrono_vehicle/ChVehicleModelData.h" -#include "chrono_vehicle/terrain/RigidTerrain.h" -#include "chrono_vehicle/driver/ChIrrGuiDriver.h" -#include "chrono_vehicle/driver/ChPathFollowerDriver.h" -#include "chrono_vehicle/wheeled_vehicle/utils/ChWheeledVehicleIrrApp.h" -#include -#include "chrono_models/vehicle/hmmwv/HMMWV.h" - -#define PI 3.1415926535 -//using veh_status.msg -using namespace chrono; -using namespace chrono::geometry; -using namespace chrono::vehicle; -using namespace chrono::vehicle::hmmwv; - - -// ============================================================================= -// Problem parameters -// Main Data Path -//std::string data_path("/home/shreyas/.julia/v0.6/MAVs/catkin_ws/data/vehicle/"); -std::string data_path("../../../src/system/chrono/ros_chrono/src/data/vehicle/"); -//std::string data_path("src/system/chrono/ros_chrono/src/data/vehicle/"); -// Contact method type -ChMaterialSurface::ContactMethod contact_method = ChMaterialSurface::SMC; - -// Type of tire model (RIGID, LUGRE, FIALA, or PACEJKA) -TireModelType tire_model = TireModelType::RIGID; - -// Input file name for PACEJKA tires if they are selected -std::string pacejka_tire_file(data_path+"hmmwv/tire/HMMWV_pacejka.tir"); -//std::string pacejka_tire_file("hmmwv/tire/HMMWV_pacejka.tir"); -// Type of powertrain model (SHAFTS or SIMPLE) -PowertrainModelType powertrain_model = PowertrainModelType::SIMPLE; - -// Drive type (FWD, RWD, or AWD) -DrivelineType drive_type = DrivelineType::RWD; - -// Visualization type for vehicle parts (PRIMITIVES, MESH, or NONE) -VisualizationType chassis_vis_type = VisualizationType::PRIMITIVES; -VisualizationType suspension_vis_type = VisualizationType::PRIMITIVES; -VisualizationType steering_vis_type = VisualizationType::PRIMITIVES; -VisualizationType wheel_vis_type = VisualizationType::NONE; -VisualizationType tire_vis_type = VisualizationType::PRIMITIVES; -//double callback_act=0; - -// Input file names for the path-follower driver model -std::string steering_controller_file(data_path+"generic/driver/SteeringController.json"); -//std::string steering_controller_file("generic/driver/SteeringController.json"); -std::string speed_controller_file(data_path+"generic/driver/SpeedController.json"); -//std::string speed_controller_file("generic/driver/SpeedController.json"); -// std::string path_file("paths/straight.txt"); -std::string path_file(data_path+"paths/my_path.txt"); - -// std::string path_file("paths/curve.txt"); -// std::string path_file("paths/NATO_double_lane_change.txt"); -//std::string path_file(data_path+"paths/ISO_double_lane_change.txt"); -//std::string path_file("paths/ISO_double_lane_change.txt"); - - - -// Rigid terrain dimensions -double terrainHeight = 0; -double terrainLength = 1000.0; // size in X direction -double terrainWidth = 1000.0; // size in Y direction - -// Point on chassis tracked by the chase camera -ChVector<> trackPoint(0.0, 0.0, 1.75); - -// Simulation step size -double step_size = 1e-2; -double tire_step_size = step_size; - -// Simulation end time -double t_end = 100; - -// Render FPS -double fps = 60; - -// Debug logging -bool debug_output = false; -double debug_fps = 10; - -// Output directories -const std::string out_dir = GetChronoOutputPath() + "STEERING_CONTROLLER"; -const std::string pov_dir = out_dir + "/POVRAY"; - -// POV-Ray output -bool povray_output = false; - -// Vehicle state output (forced to true if povray output enabled) -bool state_output = false; -int filter_window_size = 20; - - -// ============================================================================= - -// Custom Irrlicht event receiver for selecting current driver model. -class ChDriverSelector : public irr::IEventReceiver { - public: - ChDriverSelector(const ChVehicle& vehicle, ChPathFollowerDriver* driver_follower, ChIrrGuiDriver* driver_gui) - : m_vehicle(vehicle), - m_driver_follower(driver_follower), - m_driver_gui(driver_gui), - m_driver(m_driver_follower), - m_using_gui(false) {} - - ChDriver* GetDriver() { return m_driver; } - bool UsingGUI() const { return m_using_gui; } - - virtual bool OnEvent(const irr::SEvent& event) { - // Only interpret keyboard inputs. - if (event.EventType != irr::EET_KEY_INPUT_EVENT) - return false; - - // Disregard key pressed - if (event.KeyInput.PressedDown) - return false; - - switch (event.KeyInput.Key) { - case irr::KEY_COMMA: - if (m_using_gui) { - m_driver = m_driver_follower; - m_using_gui = false; - } - return true; - case irr::KEY_PERIOD: - if (!m_using_gui) { - m_driver_gui->SetThrottle(m_driver_follower->GetThrottle()); - m_driver_gui->SetSteering(m_driver_follower->GetSteering()); - m_driver_gui->SetBraking(m_driver_follower->GetBraking()); - m_driver = m_driver_gui; - m_using_gui = true; - } - return true; - case irr::KEY_HOME: - if (!m_using_gui && !m_driver_follower->GetSteeringController().IsDataCollectionEnabled()) { - std::cout << "Data collection started at t = " << m_vehicle.GetChTime() << std::endl; - m_driver_follower->GetSteeringController().StartDataCollection(); - } - return true; - case irr::KEY_END: - if (!m_using_gui && m_driver_follower->GetSteeringController().IsDataCollectionEnabled()) { - std::cout << "Data collection stopped at t = " << m_vehicle.GetChTime() << std::endl; - m_driver_follower->GetSteeringController().StopDataCollection(); - } - return true; - case irr::KEY_INSERT: - if (!m_using_gui && m_driver_follower->GetSteeringController().IsDataAvailable()) { - char filename[100]; - sprintf(filename, "controller_%.2f.out", m_vehicle.GetChTime()); - std::cout << "Data written to file " << filename << std::endl; - m_driver_follower->GetSteeringController().WriteOutputFile(std::string(filename)); - } - return true; - default: - break; - } - - return false; - } - - private: - bool m_using_gui; - const ChVehicle& m_vehicle; - ChPathFollowerDriver* m_driver_follower; - ChIrrGuiDriver* m_driver_gui; - ChDriver* m_driver; -}; - -struct parameters -{ - RigidTerrain terrain; - HMMWV_Reduced my_hmmwv; - ChRealtimeStepTimer realtime_timer; - int sim_frame; - double callback_act; - double steering_input; - double throttle_input; - double braking_input; - irr::scene::IMeshSceneNode* ballS; - irr::scene::IMeshSceneNode* ballT; -} ; -//----------------------callback - -void controlCallback(const traj_gen_chrono::Trajectory::ConstPtr &msg, parameters &hmmwv_params,ChVehicleIrrApp &app,ChIrrGuiDriver &driver_gui, -double &target_speed,double &time,ros_chrono_msgs::veh_status &data_out, ros::Publisher &vehicleinfo_pub){ - - app.SetPaused(1); - - std::vector x_vec=msg->x; - std::vector y_vec=msg->y; -// ROS_INFO("I heard: [%f]", x_vec[0]); - //ROS_INFO_STREAM(msg); - double num_pts = x_vec.size(); - double num_cols = 3; - double z_val = 0.5; - std::ofstream myfile; - myfile.open(path_file,std::ofstream::out | std::ofstream::trunc); - - myfile << ' ' << num_pts << ' '<< num_cols << '\n'; - for (int pt_cnt=0; pt_cntrun()) { - - if (sim_frame == 0) { - - app.BeginScene(true, true, irr::video::SColor(255, 140, 161, 192)); - app.DrawAll(); - app.EndScene(); - /* - if (povray_output) { - char filename[100]; - sprintf(filename, "%s/data_%03d.dat", pov_dir.c_str(), render_frame + 1); - utils::WriteShapesPovray(my_hmmwv.GetSystem(), filename); - } - - if (state_output) { - csv << time << steering_input << throttle_input << braking_input; - csv << my_hmmwv.GetVehicle().GetVehicleSpeed(); - csv << acc_CG.x() << fwd_acc_CG << acc_CG.y() << lat_acc_CG; - csv << acc_driver.x() << fwd_acc_driver << acc_driver.y() << lat_acc_driver; - csv << std::endl; - }*/ - - render_frame++; - } - const ChVector<> pS = driver_follower.GetSteeringController().GetSentinelLocation(); - const ChVector<> pT = driver_follower.GetSteeringController().GetTargetLocation(); - hmmwv_params.ballS->setPosition(irr::core::vector3df((irr::f32)pS.x(), (irr::f32)pS.y(), (irr::f32)pS.z())); - hmmwv_params.ballT->setPosition(irr::core::vector3df((irr::f32)pT.x(), (irr::f32)pT.y(), (irr::f32)pT.z())); - - time = hmmwv_params.my_hmmwv.GetSystem()->GetChTime(); - // End simulation - if (time >= t_end) - break; - hmmwv_params.throttle_input = selector.GetDriver()->GetThrottle(); - hmmwv_params.steering_input = selector.GetDriver()->GetSteering(); - hmmwv_params.braking_input = selector.GetDriver()->GetBraking(); - driver_follower.Synchronize(time); - driver_gui.Synchronize(time); - hmmwv_params.terrain.Synchronize(time); - hmmwv_params.my_hmmwv.Synchronize(time, hmmwv_params.steering_input, hmmwv_params.braking_input, hmmwv_params.throttle_input, hmmwv_params.terrain); - std::string msg1 = selector.UsingGUI() ? "GUI driver" : "Follower driver"; - app.Synchronize(msg1, hmmwv_params.steering_input, hmmwv_params.throttle_input, hmmwv_params.braking_input); - - // Advance simulation for one timestep for all modules - double step = hmmwv_params.realtime_timer.SuggestSimulationStep(step_size); - driver_follower.Advance(step); - driver_gui.Advance(step); - hmmwv_params.terrain.Advance(step); - hmmwv_params.my_hmmwv.Advance(step); - app.Advance(step); - - // Increment simulation frame number - hmmwv_params.sim_frame++; - hmmwv_params.callback_act=1; - - ChVector<> global_pos = hmmwv_params.my_hmmwv.GetVehicle().GetVehicleCOMPos();//global location of chassis reference frame origin - ChQuaternion<> global_orntn = hmmwv_params.my_hmmwv.GetVehicle().GetVehicleRot();//global orientation as quaternion - ChVector<> rot_dt = hmmwv_params.my_hmmwv.GetVehicle().GetChassisBody()->GetWvel_loc();//global orientation as quaternion - ChVector<> global_velCOM = hmmwv_params.my_hmmwv.GetVehicle().GetChassisBody()->GetPos_dt(); - ChVector<> global_accCOM = hmmwv_params.my_hmmwv.GetVehicle().GetChassisBody()->GetPos_dtdt(); - //ChVector<> euler_ang = global_orntn.Q_to_Rotv(); //convert to euler angles - double q0 = global_orntn[0]; - double q1 = global_orntn[1]; - double q2 = global_orntn[2]; - double q3 = global_orntn[3]; - double yaw_val=atan2(2*(q0*q3+q1*q2),1-2*(q2*q2+q3*q3)); - - if (yaw_val<0){ - yaw_val=-yaw_val+PI/2; - } - else if (yaw_val>=0 && yaw_val<=PI/2){ - yaw_val=PI/2-yaw_val; - } - else if (yaw_val>PI/2 && yaw_val<=PI){ - yaw_val=5*PI/2-yaw_val; - } - //ChPacejkaTire<> slip_angle = GetSlipAngle() - double slip_angle = hmmwv_params.my_hmmwv.GetTire(0)->GetLongitudinalSlip(); - - - data_out.t_chrono=time; //time in chrono simulation - data_out.x_pos= global_pos[0] ; - data_out.y_pos=global_pos[1]; - data_out.x_v= fabs(global_velCOM[0]); //speed measured at the origin of the chassis reference frame. - data_out.y_v= global_velCOM[1]; - data_out.x_a= global_accCOM[0]; - data_out.yaw_curr=yaw_val; //in radians - data_out.yaw_rate=-rot_dt[2];//(yaw_val-yaw_prev_val)/(time-t_prev_val); //in radians - data_out.sa=slip_angle; - data_out.thrt_in=hmmwv_params.throttle_input; //throttle input in the range [0,+1] - data_out.brk_in=hmmwv_params.braking_input; //braking input in the range [0,+1] - data_out.str_in=hmmwv_params.steering_input; //steeering input in the range [-1,+1] - - vehicleinfo_pub.publish(data_out); - ros::spinOnce(); - } -} - -// ============================================================================= -int main(int argc, char* argv[]) { - - -char cwd[1024]; - if (getcwd(cwd, sizeof(cwd)) != NULL) - fprintf(stdout, "Current working dir: %s\n", cwd); - else - perror("getcwd() error"); - GetLog() << "Copyright (c) 2017 projectchrono.org\nChrono version: " << CHRONO_VERSION << "\n\n"; - - SetChronoDataPath(CHRONO_DATA_DIR); - vehicle::SetDataPath("opt/chrono/chrono/data/vehicle"); - // std::cout << GetChronoDataPath() << "\n"; check path of chrono data folder - // Initialize ROS Chrono node and set node handle to n - - ros::init(argc, argv, "Chronode"); - ros::NodeHandle n; - // Desired vehicle speed (m/s) - double target_speed; - n.getParam("v_des",target_speed); - - //Initial Position - double x0, y0, z0, psi; - bool gui_switch; - n.getParam("x",x0); - n.getParam("y",y0); - n.getParam("z",z0); - n.getParam("x",x0); - n.getParam("x",x0); - n.getParam("gui_status",gui_switch); - - // Initial vehicle location and orientation - ChVector<> initLoc(x0, y0, z0); - ChQuaternion<> initRot(cos(PI/4), 0, 0, sin(PI/4)); //initial yaw of pi/2 - - ros::Publisher vehicleinfo_pub = n.advertise("vehicleinfo", 1); - //ros::Rate loop_rate(5); - - // ------------------------------ - // Create the vehicle and terrain - // ------------------------------ - - // Create the HMMWV vehicle, set parameters, and initialize - HMMWV_Reduced my_hmmwv; - my_hmmwv.SetContactMethod(contact_method); - my_hmmwv.SetChassisFixed(false); - my_hmmwv.SetInitPosition(ChCoordsys<>(initLoc, initRot)); - my_hmmwv.SetPowertrainType(powertrain_model); - my_hmmwv.SetDriveType(drive_type); - my_hmmwv.SetTireType(tire_model); - my_hmmwv.SetTireStepSize(tire_step_size); - my_hmmwv.SetPacejkaParamfile(pacejka_tire_file); - my_hmmwv.Initialize(); - - my_hmmwv.SetChassisVisualizationType(chassis_vis_type); - my_hmmwv.SetSuspensionVisualizationType(suspension_vis_type); - my_hmmwv.SetSteeringVisualizationType(steering_vis_type); - my_hmmwv.SetWheelVisualizationType(wheel_vis_type); - my_hmmwv.SetTireVisualizationType(tire_vis_type); - - // Create the terrain - RigidTerrain terrain(my_hmmwv.GetSystem()); - terrain.SetContactFrictionCoefficient(0.9f); - terrain.SetContactRestitutionCoefficient(0.01f); - terrain.SetContactMaterialProperties(2e7f, 0.3f); - terrain.SetColor(ChColor(1, 1, 1)); - //terrain.SetTexture(chrono::vehicle::GetDataFile("terrain/textures/tile4.jpg"), 200, 200); - terrain.SetTexture(data_path+"terrain/textures/tile4.jpg", 200, 200); - terrain.Initialize(terrainHeight, terrainLength, terrainWidth); - - // ---------------------- - // Create the Bezier path - // ---------------------- - - auto path = ChBezierCurve::read(path_file); - - - // --------------------------------------- - // Create the vehicle Irrlicht application - // --------------------------------------- - - ChVehicleIrrApp app(&my_hmmwv.GetVehicle(), &my_hmmwv.GetPowertrain(), L"Steering Controller Demo", - irr::core::dimension2d(800, 640)); - - app.SetHUDLocation(500, 20); - app.SetSkyBox(); - app.AddTypicalLogo(); - app.AddTypicalLights(irr::core::vector3df(-150.f, -150.f, 200.f), irr::core::vector3df(-150.f, 150.f, 200.f), 100, - 100); - app.AddTypicalLights(irr::core::vector3df(150.f, -150.f, 200.f), irr::core::vector3df(150.0f, 150.f, 200.f), 100, - 100); - app.EnableGrid(false); - app.SetChaseCamera(trackPoint, 6.0, 0.5); - - app.SetTimestep(step_size); - - // Visualization of controller points (sentinel & target) - irr::scene::IMeshSceneNode* ballS = app.GetSceneManager()->addSphereSceneNode(0.1f); - irr::scene::IMeshSceneNode* ballT = app.GetSceneManager()->addSphereSceneNode(0.1f); - ballS->getMaterial(0).EmissiveColor = irr::video::SColor(0, 255, 0, 0); - ballT->getMaterial(0).EmissiveColor = irr::video::SColor(0, 0, 255, 0); - - // ------------------------- - // Create the driver systems - // ------------------------- - - // Create both a GUI driver and a path-follower and allow switching between them - ChIrrGuiDriver driver_gui(app); - driver_gui.Initialize(); - - /*Trajectory - ChPathFollowerDriver driver_follower(my_hmmwv.GetVehicle(), path, "my_path", target_speed); - driver_follower.GetSteeringController().SetLookAheadDistance(5); - driver_follower.GetSteeringController().SetGains(0.5, 0, 0); - driver_follower.GetSpeedController().SetGains(0.4, 0, 0); - */ - ChPathFollowerDriver driver_follower(my_hmmwv.GetVehicle(), steering_controller_file, - speed_controller_file, path, "my_path", target_speed); - driver_follower.Initialize(); - - // Create and register a custom Irrlicht event receiver to allow selecting the - // current driver model. - ChDriverSelector selector(my_hmmwv.GetVehicle(), &driver_follower, &driver_gui); - app.SetUserEventReceiver(&selector); - - // Finalize construction of visualization assets - app.AssetBindAll(); - app.AssetUpdateAll(); - - // ----------------- - // Initialize output - // ----------------- - - state_output = state_output || povray_output; - - if (state_output) { - if (ChFileutils::MakeDirectory(out_dir.c_str()) < 0) { - std::cout << "Error creating directory " << out_dir << std::endl; - return 1; - } - } - - if (povray_output) { - if (ChFileutils::MakeDirectory(pov_dir.c_str()) < 0) { - std::cout << "Error creating directory " << pov_dir << std::endl; - return 1; - } - driver_follower.ExportPathPovray(out_dir); - } - - utils::CSV_writer csv("\t"); - csv.stream().setf(std::ios::scientific | std::ios::showpos); - csv.stream().precision(6); - - utils::ChRunningAverage fwd_acc_GC_filter(filter_window_size); - utils::ChRunningAverage lat_acc_GC_filter(filter_window_size); - - utils::ChRunningAverage fwd_acc_driver_filter(filter_window_size); - utils::ChRunningAverage lat_acc_driver_filter(filter_window_size); - - // --------------- - // Simulation loop - // --------------- - - // Driver location in vehicle local frame - ChVector<> driver_pos = my_hmmwv.GetChassis()->GetLocalDriverCoordsys().pos; - // Number of simulation steps between miscellaneous events - double render_step_size = 1 / fps; - int render_steps = (int)std::ceil(render_step_size / step_size); - double debug_step_size = 1 / debug_fps; - int debug_steps = (int)std::ceil(debug_step_size / step_size); - - // Initialize simulation frame counter and simulation time - ChRealtimeStepTimer realtime_timer; - int sim_frame = 0; - int render_frame = 0; - - double callback_act; - double throttle_input, steering_input, braking_input; - parameters hmmwv_params{terrain,my_hmmwv,realtime_timer,sim_frame,callback_act,steering_input,throttle_input,braking_input,ballS,ballT}; - - std::ofstream myfile1; - myfile1.open(data_path+"paths/position.txt",std::ofstream::out | std::ofstream::trunc); - // bool new_path=0; - while (app.GetDevice()->run()) { - double time = my_hmmwv.GetSystem()->GetChTime(); - - /* - // Hack for acceleration-braking maneuver - static bool braking = false; - if (my_hmmwv.GetVehicle().GetVehicleSpeed() > target_speed) - braking = true; - if (braking) { - throttle_input = 0; - braking_input = 1; - } else { - throttle_input = 1; - braking_input = 0; - } - */ - - // ros::Subscriber sub = n.subscribe("desired_ref", 1, ¶meters::controlCallback, &hmmwv_params); - - // Render scene and output POV-Ray data - if (sim_frame==-1){ //if (sim_frame % render_steps == 0) { - - app.BeginScene(true, true, irr::video::SColor(255, 140, 161, 192)); - app.DrawAll(); - app.EndScene(); - - /* if (povray_output) { - char filename[100]; - sprintf(filename, "%s/data_%03d.dat", pov_dir.c_str(), render_frame + 1); - utils::WriteShapesPovray(my_hmmwv.GetSystem(), filename); - } - - if (state_output) { - csv << time << steering_input << throttle_input << braking_input; - csv << my_hmmwv.GetVehicle().GetVehicleSpeed(); - csv << acc_CG.x() << fwd_acc_CG << acc_CG.y() << lat_acc_CG; - csv << acc_driver.x() << fwd_acc_driver << acc_driver.y() << lat_acc_driver; - csv << std::endl; - }*/ - - render_frame++; - } -/* - // Debug logging - if (debug_output && sim_frame % debug_steps == 0) { - GetLog() << "driver acceleration: " << acc_driver.x() << " " << acc_driver.y() << " " << acc_driver.z() - << "\n"; - GetLog() << "CG acceleration: " << acc_CG.x() << " " << acc_CG.y() << " " << acc_CG.z() << "\n"; - GetLog() << "\n"; - }*/ - callback_act=0; - ros_chrono_msgs::veh_status data_out; - - ros::Subscriber sub = n.subscribe("desired_ref", 10, boost::bind(controlCallback, _1, boost::ref(hmmwv_params),boost::ref(app),boost::ref(driver_gui), - boost::ref(target_speed),boost::ref(time),boost::ref(data_out),boost::ref(vehicleinfo_pub))); -// ros::Subscriber sub = n.subscribe("desired_ref", 10, boost::bind(controlCallback, _1, boost::ref(hmmwv_params),boost::ref(app))); - // if (sub){ - std::cout << callback_act; - // } - - // app.SetPaused(1); - path = ChBezierCurve::read(path_file); - - ChVector<> acc_CG = my_hmmwv.GetVehicle().GetChassisBody()->GetPos_dtdt(); - ChVector<> acc_driver = my_hmmwv.GetVehicle().GetVehicleAcceleration(driver_pos); - double fwd_acc_CG = fwd_acc_GC_filter.Add(acc_CG.x()); - double lat_acc_CG = lat_acc_GC_filter.Add(acc_CG.y()); - double fwd_acc_driver = fwd_acc_driver_filter.Add(acc_driver.x()); - double lat_acc_driver = lat_acc_driver_filter.Add(acc_driver.y()); - - - // End simulation - if (time >= t_end) - break; - - - // Update sentinel and target location markers for the path-follower controller. - // Note that we do this whether or not we are currently using the path-follower driver. - - const ChVector<> pS = driver_follower.GetSteeringController().GetSentinelLocation(); - const ChVector<> pT = driver_follower.GetSteeringController().GetTargetLocation(); - ballS->setPosition(irr::core::vector3df((irr::f32)pS.x(), (irr::f32)pS.y(), (irr::f32)pS.z())); - ballT->setPosition(irr::core::vector3df((irr::f32)pT.x(), (irr::f32)pT.y(), (irr::f32)pT.z())); - ros::spin(); - /* time = hmmwv_params.my_hmmwv.GetSystem()->GetChTime(); - hmmwv_params.throttle_input = selector.GetDriver()->GetThrottle(); - hmmwv_params.steering_input = selector.GetDriver()->GetSteering(); - hmmwv_params.braking_input = selector.GetDriver()->GetBraking(); - // Update modules (process inputs from other modules) - driver_follower.Synchronize(time); - driver_gui.Synchronize(time); - terrain.Synchronize(time); - hmmwv_params.my_hmmwv.Synchronize(time, hmmwv_params.steering_input, hmmwv_params.braking_input, hmmwv_params.throttle_input, terrain); - std::string msg = selector.UsingGUI() ? "GUI driver" : "Follower driver"; - app.Synchronize(msg, hmmwv_params.steering_input, hmmwv_params.throttle_input, hmmwv_params.braking_input); - - // Advance simulation for one timestep for all modules - double step = realtime_timer.SuggestSimulationStep(step_size); - driver_follower.Advance(step); - driver_gui.Advance(step); - terrain.Advance(step); - hmmwv_params.my_hmmwv.Advance(step); - app.Advance(step); - - // Increment simulation frame number - sim_frame++;*/ - - ChVector<> global_pos = hmmwv_params.my_hmmwv.GetVehicle().GetVehicleCOMPos();//global location of chassis reference frame origin - ChQuaternion<> global_orntn = hmmwv_params.my_hmmwv.GetVehicle().GetVehicleRot();//global orientation as quaternion - ChVector<> rot_dt = hmmwv_params.my_hmmwv.GetVehicle().GetChassisBody()->GetWvel_loc();//global orientation as quaternion - ChVector<> global_velCOM = hmmwv_params.my_hmmwv.GetVehicle().GetChassisBody()->GetPos_dt(); - ChVector<> global_accCOM = hmmwv_params.my_hmmwv.GetVehicle().GetChassisBody()->GetPos_dtdt(); - //ChVector<> euler_ang = global_orntn.Q_to_Rotv(); //convert to euler angles - double q0 = global_orntn[0]; - double q1 = global_orntn[1]; - double q2 = global_orntn[2]; - double q3 = global_orntn[3]; - double yaw_val=atan2(2*(q0*q3+q1*q2),1-2*(q2*q2+q3*q3)); - - if (yaw_val<0){ - yaw_val=-yaw_val+PI/2; - } - else if (yaw_val>=0 && yaw_val<=PI/2){ - yaw_val=PI/2-yaw_val; - } - else if (yaw_val>PI/2 && yaw_val<=PI){ - yaw_val=5*PI/2-yaw_val; - } - //ChPacejkaTire<> slip_angle = GetSlipAngle() - double slip_angle = hmmwv_params.my_hmmwv.GetTire(0)->GetLongitudinalSlip(); - - - data_out.t_chrono=time; //time in chrono simulation - data_out.x_pos= global_pos[0] ; - data_out.y_pos=global_pos[1]; - data_out.x_v= fabs(global_velCOM[0]); //speed measured at the origin of the chassis reference frame. - data_out.y_v= global_velCOM[1]; - data_out.x_a= global_accCOM[0]; - data_out.yaw_curr=yaw_val; //in radians - data_out.yaw_rate=-rot_dt[2];//(yaw_val-yaw_prev_val)/(time-t_prev_val); //in radians - data_out.sa=slip_angle; - data_out.thrt_in=throttle_input; //throttle input in the range [0,+1] - data_out.brk_in=braking_input; //braking input in the range [0,+1] - data_out.str_in=steering_input; //steeering input in the range [-1,+1] - - vehicleinfo_pub.publish(data_out); - // loop_rate.sleep(); - - - myfile1 << ' ' << global_pos[0] << ' '<< global_pos[1] <<' ' << global_pos[2] << '\n'; - } - - if (state_output){ - csv.write_to_file(out_dir + "/state.out"); - } - -//} - -myfile1.close(); - - return 0; -} diff --git a/ros/src/models/chrono/ros_chrono/old/test_1.cpp b/ros/src/models/chrono/ros_chrono/old/test_1.cpp deleted file mode 100644 index 8c3185ca..00000000 --- a/ros/src/models/chrono/ros_chrono/old/test_1.cpp +++ /dev/null @@ -1,309 +0,0 @@ -// ============================================================================= -// PROJECT CHRONO - http://projectchrono.org -// -// Copyright (c) 2014 projectchrono.org -// All rights reserved. -// -// Use of this source code is governed by a BSD-style license that can be found -// in the LICENSE file at the top level of the distribution and at -// http://projectchrono.org/license-chrono.txt. -// -// ============================================================================= -// Authors: Radu Serban, Justin Madsen -// ============================================================================= -// -// Main driver function for the HMMWV full model. -// -// The vehicle reference frame has Z up, X towards the front of the vehicle, and -// Y pointing to the left. -// -// ============================================================================= - -#include "chrono/core/ChFileutils.h" -#include "chrono/core/ChStream.h" -#include "chrono/core/ChRealtimeStep.h" -#include "chrono/utils/ChUtilsInputOutput.h" - -#include "chrono_vehicle/ChConfigVehicle.h" -#include "chrono_vehicle/ChVehicleModelData.h" -#include "chrono_vehicle/terrain/RigidTerrain.h" -#include "chrono_vehicle/driver/ChIrrGuiDriver.h" -#include "chrono_vehicle/driver/ChDataDriver.h" -#include "chrono_vehicle/wheeled_vehicle/utils/ChWheeledVehicleIrrApp.h" - -#include "chrono_models/vehicle/hmmwv/HMMWV.h" - - -// Added -#include -#include -#include "ros/ros.h" -#include "std_msgs/String.h" -#include "ros_chrono_msgs/veh_status.h" -#include "nloptcontrol_planner/Trajectory.h" -// -using namespace chrono; -using namespace chrono::irrlicht; -using namespace chrono::vehicle; -using namespace chrono::vehicle::hmmwv; - -// ============================================================================= - -// Initial vehicle location and orientation -ChVector<> initLoc(0, 0, 1.6); -ChQuaternion<> initRot(1, 0, 0, 0); -// ChQuaternion<> initRot(0.866025, 0, 0, 0.5); -// ChQuaternion<> initRot(0.7071068, 0, 0, 0.7071068); -// ChQuaternion<> initRot(0.25882, 0, 0, 0.965926); -// ChQuaternion<> initRot(0, 0, 0, 1); - -enum DriverMode { DEFAULT, RECORD, PLAYBACK }; -DriverMode driver_mode = DEFAULT; - -// Visualization type for vehicle parts (PRIMITIVES, MESH, or NONE) -VisualizationType chassis_vis_type = VisualizationType::PRIMITIVES; -VisualizationType suspension_vis_type = VisualizationType::PRIMITIVES; -VisualizationType steering_vis_type = VisualizationType::PRIMITIVES; -VisualizationType wheel_vis_type = VisualizationType::NONE; - -// Collision type for chassis (PRIMITIVES, MESH, or NONE) -ChassisCollisionType chassis_collision_type = ChassisCollisionType::NONE; - -// Type of powertrain model (SHAFTS, SIMPLE) -PowertrainModelType powertrain_model = PowertrainModelType::SHAFTS; - -// Drive type (FWD, RWD, or AWD) -DrivelineType drive_type = DrivelineType::AWD; - -// Type of tire model (RIGID, RIGID_MESH, PACEJKA, LUGRE, FIALA) -TireModelType tire_model = TireModelType::RIGID; - -// Rigid terrain -RigidTerrain::Type terrain_model = RigidTerrain::FLAT; -bool terrain_vis = true; -double terrainHeight = 0; // terrain height (FLAT terrain only) -double terrainLength = 100.0; // size in X direction -double terrainWidth = 100.0; // size in Y direction - -// Point on chassis tracked by the camera -ChVector<> trackPoint(0.0, 0.0, 1.75); - -// Contact method -ChMaterialSurface::ContactMethod contact_method = ChMaterialSurface::SMC; -bool contact_vis = false; - -// Simulation step sizes -double step_size = 1e-3; -double tire_step_size = step_size; - -// Simulation end time -double t_end = 1000; - -// Time interval between two render frames -double render_step_size = 1.0 / 50; // FPS = 50 - -// Output directories -const std::string out_dir = GetChronoOutputPath() + "HMMWV"; -const std::string pov_dir = out_dir + "/POVRAY"; - -// Debug logging -bool debug_output = false; -double debug_step_size = 1.0 / 1; // FPS = 1 - -// POV-Ray output -bool povray_output = false; - -// ============================================================================= - -int main(int argc, char* argv[]) { - GetLog() << "Copyright (c) 2017 projectchrono.org\nChrono version: " << CHRONO_VERSION << "\n\n"; - - ros::init(argc, argv, "test_1"); - ros::NodeHandle n; - - // -------------- - // Create systems - // -------------- - - // Create the HMMWV vehicle, set parameters, and initialize - HMMWV_Full my_hmmwv; - my_hmmwv.SetContactMethod(contact_method); - my_hmmwv.SetChassisCollisionType(chassis_collision_type); - my_hmmwv.SetChassisFixed(false); - my_hmmwv.SetInitPosition(ChCoordsys<>(initLoc, initRot)); - my_hmmwv.SetPowertrainType(powertrain_model); - my_hmmwv.SetDriveType(drive_type); - my_hmmwv.SetTireType(tire_model); - my_hmmwv.SetTireStepSize(tire_step_size); - my_hmmwv.SetPacejkaParamfile("data/vehicle/hmmwv/tire/HMMWV_pacejka.tir"); - my_hmmwv.Initialize(); - - VisualizationType tire_vis_type = - (tire_model == TireModelType::RIGID_MESH) ? VisualizationType::MESH : VisualizationType::PRIMITIVES; - - my_hmmwv.SetChassisVisualizationType(chassis_vis_type); - my_hmmwv.SetSuspensionVisualizationType(suspension_vis_type); - my_hmmwv.SetSteeringVisualizationType(steering_vis_type); - my_hmmwv.SetWheelVisualizationType(wheel_vis_type); - my_hmmwv.SetTireVisualizationType(tire_vis_type); - - // Create the terrain - RigidTerrain terrain(my_hmmwv.GetSystem()); - terrain.SetContactFrictionCoefficient(0.9f); - terrain.SetContactRestitutionCoefficient(0.01f); - terrain.SetContactMaterialProperties(2e7f, 0.3f); - terrain.SetColor(ChColor(0.8f, 0.8f, 0.5f)); - terrain.EnableVisualization(terrain_vis); - switch (terrain_model) { - case RigidTerrain::FLAT: - terrain.SetTexture(vehicle::GetDataFile("data/vehicle/terrain/textures/tile4.jpg"), 200, 200); - terrain.Initialize(terrainHeight, terrainLength, terrainWidth); - break; - case RigidTerrain::HEIGHT_MAP: - terrain.SetTexture(vehicle::GetDataFile("data/vehicle/terrain/textures/grass.jpg"), 16, 16); - terrain.Initialize(vehicle::GetDataFile("data/vehicle/terrain/height_maps/test64.bmp"), "test64", 128, 128, 0, 4); - break; - case RigidTerrain::MESH: - terrain.SetTexture(vehicle::GetDataFile("data/vehicle/terrain/textures/grass.jpg"), 100, 100); - terrain.Initialize(vehicle::GetDataFile("data/vehicle/terrain/meshes/test.obj"), "test_mesh"); - break; - } - - // Create the vehicle Irrlicht interface - ChWheeledVehicleIrrApp app(&my_hmmwv.GetVehicle(), &my_hmmwv.GetPowertrain(), L"HMMWV Demo"); - app.SetSkyBox(); - app.AddTypicalLights(irr::core::vector3df(30.f, -30.f, 100.f), irr::core::vector3df(30.f, 50.f, 100.f), 250, 130); - app.SetChaseCamera(trackPoint, 6.0, 0.5); - app.SetTimestep(step_size); - app.AssetBindAll(); - app.AssetUpdateAll(); - - // ----------------- - // Initialize output - // ----------------- - - if (ChFileutils::MakeDirectory(out_dir.c_str()) < 0) { - std::cout << "Error creating directory " << out_dir << std::endl; - return 1; - } - if (povray_output) { - if (ChFileutils::MakeDirectory(pov_dir.c_str()) < 0) { - std::cout << "Error creating directory " << pov_dir << std::endl; - return 1; - } - terrain.ExportMeshPovray(out_dir); - } - - std::string driver_file = out_dir + "/driver_inputs.txt"; - utils::CSV_writer driver_csv(" "); - - // ------------------------ - // Create the driver system - // ------------------------ - - // Create the interactive driver system - ChIrrGuiDriver driver(app); - - // Set the time response for steering and throttle keyboard inputs. - double steering_time = 1.0; // time to go from 0 to +1 (or from 0 to -1) - double throttle_time = 1.0; // time to go from 0 to +1 - double braking_time = 0.3; // time to go from 0 to +1 - driver.SetSteeringDelta(render_step_size / steering_time); - driver.SetThrottleDelta(render_step_size / throttle_time); - driver.SetBrakingDelta(render_step_size / braking_time); - - // If in playback mode, attach the data file to the driver system and - // force it to playback the driver inputs. - if (driver_mode == PLAYBACK) { - driver.SetInputDataFile(driver_file); - driver.SetInputMode(ChIrrGuiDriver::DATAFILE); - } - - driver.Initialize(); - - // --------------- - // Simulation loop - // --------------- - - if (debug_output) { - GetLog() << "\n\n============ System Configuration ============\n"; - my_hmmwv.LogHardpointLocations(); - } - - // Number of simulation steps between miscellaneous events - int render_steps = (int)std::ceil(render_step_size / step_size); - int debug_steps = (int)std::ceil(debug_step_size / step_size); - - // Initialize simulation frame counter and simulation time - ChRealtimeStepTimer realtime_timer; - int step_number = 0; - int render_frame = 0; - double time = 0; - - if (contact_vis) { - app.SetSymbolscale(1e-4); - app.SetContactsDrawMode(ChIrrTools::eCh_ContactsDrawMode::CONTACT_FORCES); - } - - while (app.GetDevice()->run()) { - time = my_hmmwv.GetSystem()->GetChTime(); - - // End simulation - if (time >= t_end) - break; - - // Render scene and output POV-Ray data - if (step_number % render_steps == 0) { - app.BeginScene(true, true, irr::video::SColor(255, 140, 161, 192)); - app.DrawAll(); - app.EndScene(); - - if (povray_output) { - char filename[100]; - sprintf(filename, "%s/data_%03d.dat", pov_dir.c_str(), render_frame + 1); - utils::WriteShapesPovray(my_hmmwv.GetSystem(), filename); - } - - render_frame++; - } - - // Debug logging - if (debug_output && step_number % debug_steps == 0) { - GetLog() << "\n\n============ System Information ============\n"; - GetLog() << "Time = " << time << "\n\n"; - my_hmmwv.DebugLog(OUT_SPRINGS | OUT_SHOCKS | OUT_CONSTRAINTS); - } - - // Collect output data from modules (for inter-module communication) - double throttle_input = driver.GetThrottle(); - double steering_input = driver.GetSteering(); - double braking_input = driver.GetBraking(); - - // Driver output - if (driver_mode == RECORD) { - driver_csv << time << steering_input << throttle_input << braking_input << std::endl; - } - - // Update modules (process inputs from other modules) - driver.Synchronize(time); - terrain.Synchronize(time); - my_hmmwv.Synchronize(time, steering_input, braking_input, throttle_input, terrain); - app.Synchronize(driver.GetInputModeAsString(), steering_input, throttle_input, braking_input); - - // Advance simulation for one timestep for all modules - double step = realtime_timer.SuggestSimulationStep(step_size); - driver.Advance(step); - terrain.Advance(step); - my_hmmwv.Advance(step); - app.Advance(step); - - // Increment frame number - step_number++; - } - - if (driver_mode == RECORD) { - driver_csv.write_to_file(driver_file); - } - - return 0; -} diff --git a/ros/src/models/chrono/ros_chrono/old/trajectory_follower.cpp b/ros/src/models/chrono/ros_chrono/old/trajectory_follower.cpp deleted file mode 100644 index 64cb4f68..00000000 --- a/ros/src/models/chrono/ros_chrono/old/trajectory_follower.cpp +++ /dev/null @@ -1,1019 +0,0 @@ -// ============================================================================= -// PROJECT CHRONO - http://projectchrono.org -// -// Copyright (c) 2014 projectchrono.org -// All rights reserved. -// -// Use of this source code is governed by a BSD-style license that can be found -// in the LICENSE file at the top level of the distribution and at -// http://projectchrono.org/license-chrono.txt. -// -// ============================================================================= -// Authors: Radu Serban -// ============================================================================= -// -// Demonstration of a steering path-follower PID controller. -// -// The vehicle reference frame has Z up, X towards the front of the vehicle, and -// Y pointing to the left. -// TO DO: -// Find proper yaw rate calculation -// Subsscribe to msg from obstacle_avoidance_chrono, callback to that to calculate ChBezierCurve -// ============================================================================= - -#include -#include -#include "boost/bind.hpp" -#include "chrono/core/ChFileutils.h" -#include "chrono/core/ChRealtimeStep.h" -#include "chrono/utils/ChFilters.h" -#include -#include -#include "ros/ros.h" -#include "std_msgs/String.h" -#include "ros_chrono_msgs/veh_status.h" -#include "nloptcontrol_planner/Trajectory.h" -#include -#include -#include -#include -#include -#include -//#include "tf/tf.h" -#include -#include "chrono_vehicle/ChVehicleModelData.h" -#include "chrono_vehicle/terrain/RigidTerrain.h" -#include "chrono_vehicle/driver/ChIrrGuiDriver.h" -#include "chrono_vehicle/driver/ChPathFollowerDriver.h" -#include "chrono_vehicle/wheeled_vehicle/utils/ChWheeledVehicleIrrApp.h" -#include "chrono_models/vehicle/hmmwv/HMMWV.h" -#include "chrono/physics/ChSystem.h" -#include "chrono_vehicle/wheeled_vehicle/tire/ChPacejkaTire.h" -//#include "chrono_models/vehicle/hmmwv/HMMWV_Pac02Tire.h" -#include "chrono_vehicle/wheeled_vehicle/tire/RigidTire.h" -#include "chrono_vehicle/wheeled_vehicle/tire/LugreTire.h" -#include "chrono_models/vehicle/hmmwv/HMMWV_ReissnerTire.h" -#include "chrono_vehicle/ChSubsysDefs.h" -#include "chrono_vehicle/wheeled_vehicle/vehicle/WheeledVehicle.h" -#include "chrono_vehicle/powertrain/ChShaftsPowertrain.h" -#include "chrono_vehicle/powertrain/SimplePowertrain.h" -#include "chrono_thirdparty/rapidjson/document.h" -#include "chrono_thirdparty/rapidjson/filereadstream.h" - -#include "chrono/core/ChFileutils.h" -#include "chrono/core/ChStream.h" -#include "chrono/utils/ChFilters.h" -#include "chrono/utils/ChUtilsInputOutput.h" -#include "chrono/solver/ChSolverMINRES.h" -#include "chrono_vehicle/ChConfigVehicle.h" - -#define PI 3.1415926535 -//using veh_status.msg -using namespace chrono; -using namespace chrono::geometry; -using namespace chrono::vehicle; -using namespace chrono::vehicle::hmmwv; - -using namespace alglib; - -using namespace rapidjson; -// ============================================================================= -// Problem parameters -// Main Data Path TODO fix this! should be a rosparam! -//std::string data_path("/home/shreyas/.julia/v0.6/MAVs/catkin_ws/data/vehicle/"); -//std::string data_path("../../../src/models/chrono/ros_chrono/src/data/vehicle/"); - -//std::string chrono_data("../../../src/models/chrono/ros_chrono/src/data/"); - -std::string data_path("MAVs/ros/src/models/chrono/ros_chrono/src/data/vehicle/"); - -std::string chrono_data("MAVs/ros/src/models/chrono/ros_chrono/src/data/"); - -//std::string data_path("src/system/chrono/ros_chrono/src/data/vehicle/"); -// Contact method type -ChMaterialSurface::ContactMethod contact_method = ChMaterialSurface::NSC; - -// Type of tire model (RIGID, LUGRE, FIALA, or PACEJKA) -// TireModelType tire_model = TireModelType::RIGID; - -// Input file name for PACEJKA tires if they are selected -std::string pacejka_tire_file_left(data_path+"hmmwv/tire/HMMWV_pacejka_left.tir"); -std::string pacejka_tire_file_right(data_path+"hmmwv/tire/HMMWV_pacejka_right.tir"); -std::string lugre_tire_file(data_path+"hmmwv/tire/HMMWV_LugreTire.json"); // Yes -std::string rigid_tire_file(data_path+"hmmwv/tire/HMMWV_RigidTire.json"); // Yes -std::string reissner_tire_file(data_path+"hmmwv/tire/HMMWV_ReissnerTire.json"); // Yes -//std::string pacejka_tire_file("hmmwv/tire/HMMWV_pacejka.tir"); -// Type of powertrain model (SHAFTS or SIMPLE) -PowertrainModelType powertrain_model = PowertrainModelType::SHAFTS; - -// Drive type (FWD, RWD, or AWD) -DrivelineType drive_type = DrivelineType::RWD; - -// Visualization type for vehicle parts (PRIMITIVES, MESH, or NONE) -VisualizationType chassis_vis_type = VisualizationType::PRIMITIVES; -VisualizationType suspension_vis_type = VisualizationType::PRIMITIVES; -VisualizationType steering_vis_type = VisualizationType::PRIMITIVES; -VisualizationType wheel_vis_type = VisualizationType::NONE; -VisualizationType tire_vis_type = VisualizationType::PRIMITIVES; - -std::string path_file(data_path+"paths/my_path.txt"); -std::string simplepowertrain_file(data_path+"hmmwv/powertrain/HMMWV_ShaftsPowertrain.json"); // Yes -WheelState wheel_states[4]; - - -// Rigid terrain dimensions -double terrainHeight = 0; -double terrainLength = 500.0; // size in X direction -double terrainWidth = 500.0; // size in Y direction - -// Point on chassis tracked by the chase camera -ChVector<> trackPoint(0.0, 0.0, 1.75); - -// Simulation step size -double step_size = 1e-2; -double tire_step_size = step_size; - -// Simulation end time -double t_end = 1000; - -// Render FPS -double fps = 60; - -// Debug logging -bool debug_output = false; -double debug_fps = 10; - -// Output directories -const std::string out_dir = GetChronoOutputPath() + "STEERING_CONTROLLER"; -const std::string pov_dir = out_dir + "/POVRAY"; - -// POV-Ray output -bool povray_output = false; - -// Vehicle state output (forced to true if povray output enabled) -bool state_output = false; -int filter_window_size = 20; - -// In src/data/vehicle/hmmwv/steering/HMMWV_PitmanArm.json revolution joint -double speed = 0.0; -double maximum_steering_angle; -// Controller output -double target_steering_interp = 0.0; -double target_speed_interp = 0.0; -double controller_output = 0.0; -double time_shift = 0.0; -PID controller; -std::vector traj_t(2,0); -std::vector traj_sa(2,0); -std::vector traj_ux(2,0); - -// ============================================================================= - -// Custom Irrlicht event receiver for selecting current driver model. -class ChDriverSelector : public irr::IEventReceiver { - public: - ChDriverSelector(const ChVehicle& vehicle, ChIrrGuiDriver* driver_gui) - : m_vehicle(vehicle), - m_driver_gui(driver_gui), - m_driver(m_driver_gui), - m_using_gui(true) {} - - ChDriver* GetDriver() { return m_driver; } - bool UsingGUI() const { return m_using_gui; } - - virtual bool OnEvent(const irr::SEvent& event) { - return false; - } - - private: - bool m_using_gui; - const ChVehicle& m_vehicle; - ChIrrGuiDriver* m_driver_gui; - ChDriver* m_driver; -}; - -struct parameters -{ - RigidTerrain terrain; - TerrainForces tire_forces; - WheeledVehicle my_hmmwv; - ChRealtimeStepTimer realtime_timer; - int sim_frame; - double steering_input; - double throttle_input; - double braking_input; - std::vector x_traj_curr; - std::vector y_traj_curr; - std::vector x_traj_prev; - std::vector y_traj_prev; - double target_speed; - int render_steps; - int render_frame; -} ; - -void waitForLoaded(ros::NodeHandle &n){ - bool planner_init = false; - std::string planner_namespace; - n.getParam("system/planner",planner_namespace); - n.getParam("system/"+planner_namespace+"/flags/initialized",planner_init); - while(!planner_init){ - usleep(500); // < my question - n.getParam("system/"+planner_namespace+"/flags/initialized",planner_init); - - } - usleep(500); //sleep another 500ms to ensure everything is loaded. - //continue on here -} - -void setChassisParams(ros::NodeHandle &n){ - std::ofstream myfile2; - - myfile2.open(data_path+"hmmwv/chassis/HMMWV_Chassis.json",std::ofstream::out | std::ofstream::trunc); // Yes - std::string s1 = "{ "; - std::string s2 = " \"Name\": \"HMMWV chassis\","; - std::string s3 = " \"Type\": \"Chassis\","; - std::string s4 = " \"Template\": \"RigidChassis\","; - std::string s5 = " \"Components\":"; - std::string s6 = " ["; - std::string s7 = " {"; - std::string s8 = " \"Centroidal Frame\": {"; - std::string s9 = " \"Location\": "; - std::string s10; - n.getParam("vehicle/chrono/vehicle_params/centroidLoc",s10); - std::string s11 = " \"Orientation\": "; - std::string s12; - n.getParam("/vehicle/chrono/vehicle_params/centroidOrientation",s12); - std::string s13 = " },"; - std::string s14 = " \"Mass\": "; - std::string s15; - n.getParam("/vehicle/chrono/vehicle_params/chassisMass",s15); - std::string s16 = " \"Moments of Inertia\": "; - std::string s17; - n.getParam("/vehicle/chrono/vehicle_params/chassisInertia",s17); - std::string s18 = " \"Products of Inertia\": [0, 0, 0],"; - std::string s19 = " \"Void\": false"; - std::string s20 = " }"; - std::string s21 = " ],"; - std::string s22 = " \"Driver Position\":"; - std::string s23 = " {"; - std::string s24 = " \"Location\": "; - std::string s25; - n.getParam("/vehicle/chrono/vehicle_params/driverLoc",s25); - std::string s26 = " \"Orientation\": "; - std::string s27; - n.getParam("/vehicle/chrono/vehicle_params/driverOrientation",s27); - std::string s28 = " },"; - std::string s29 = " \"Visualization\":"; - std::string s30 = " {"; - std::string s31 = " \"Mesh\":"; - std::string s32 = " {"; - std::string s33 = " \"Filename\": \"hmmwv/hmmwv_chassis.obj\","; - std::string s34 = " \"Name\": \"hmmwv_chassis_POV_geom\""; - std::string s35 = " }"; - std::string s36 = " }"; - std::string s37 = "}"; - myfile2 << s1 << '\n'; - myfile2 << s2 << '\n'; - myfile2 << s3 << '\n'; - myfile2 << s4 << '\n'; - myfile2 << '\n'; - myfile2 << s5 << '\n'; - myfile2 << s6 << '\n'; - myfile2 << s7 << '\n'; - myfile2 << s8 << '\n'; - myfile2 << s9 << s10 << '\n'; - myfile2 << s11 << s12 << '\n'; - myfile2 << s13 << '\n'; - myfile2 << s14 << s15 <<'\n'; - myfile2 << s16 << s17 << '\n'; - myfile2 << s18 << '\n'; - myfile2 << s19 << '\n'; - myfile2 << s20 << '\n'; - myfile2 << s21 << '\n'; - myfile2 << s22 << '\n'; - myfile2 << s23 << '\n'; - myfile2 << s24 << s25 << '\n'; - myfile2 << s26 << s27 << '\n'; - myfile2 << s28 << '\n'; - myfile2 << '\n'; - myfile2 << s29 << '\n'; - myfile2 << s30 << '\n'; - myfile2 << s31 << '\n'; - myfile2 << s32 << '\n'; - myfile2 << s33 << '\n'; - myfile2 << s34 << '\n'; - myfile2 << s35 << '\n'; - myfile2 << s36 << '\n'; - myfile2 << s37 << '\n'; - myfile2.close(); -} - -void setDrivelineParams(ros::NodeHandle &n){ - std::ofstream myfile2; - - myfile2.open(data_path+"hmmwv/driveline/HMMWV_Driveline2WD.json",std::ofstream::out | std::ofstream::trunc); // Yes - std::string s1 = "{ "; - std::string s2 = " \"Name\": \"HMMWV RWD Driveline\","; - std::string s3 = " \"Type\": \"Driveline\","; - std::string s4 = " \"Template\": \"ShaftsDriveline2WD\","; - std::string s5 = " \"Shaft Direction\":"; - std::string s6 = " {"; - std::string s7 = " \"Motor Block\": "; - std::string s8; - n.getParam("/vehicle/chrono/vehicle_params/motorBlockDirection",s8); - std::string s9 = " \"Axle\": "; - std::string s10; - n.getParam("/vehicle/chrono/vehicle_params/axleDirection",s10); - std::string s11 = " },"; - std::string s12 = " \"Shaft Inertia\":"; - std::string s13 = " {"; - std::string s14 = " \"Driveshaft\": "; - std::string s15; - n.getParam("/vehicle/chrono/vehicle_params/driveshaftInertia", s15); - std::string s16 = " \"Differential Box\": "; - std::string s17; - n.getParam("/vehicle/chrono/vehicle_params/differentialBoxInertia",s17); - std::string s18 = " },"; - std::string s19 = " \"Gear Ratio\":"; - std::string s20 = " {"; - std::string s21 = " \"Conical Gear\": "; - std::string s22; - n.getParam("/vehicle/chrono/vehicle_params/conicalGearRatio",s22); - std::string s23 = " \"Differential\": "; - std::string s24; - n.getParam("/vehicle/chrono/vehicle_params/differentialRatio",s24); - std::string s25 = " }"; - std::string s26 = "}"; - - myfile2 << s1 << '\n'; - myfile2 << s2 << '\n'; - myfile2 << s3 << '\n'; - myfile2 << s4 << '\n'; - myfile2 << '\n'; - myfile2 << s5 << '\n'; - myfile2 << s6 << '\n'; - myfile2 << s7 << s8 << '\n'; - myfile2 << s9 << s10 << '\n'; - myfile2 << s11 << '\n'; - myfile2 << '\n'; - myfile2 << s12 << '\n'; - myfile2 << s13 << '\n'; - myfile2 << s14 << s15 << '\n'; - myfile2 << s16 << s17 << '\n'; - myfile2 << s18 << '\n'; - myfile2 << '\n'; - myfile2 << s19 << '\n'; - myfile2 << s20 << '\n'; - myfile2 << s21 << s22 << '\n'; - myfile2 << s23 << s24 << '\n'; - myfile2 << s25 << '\n'; - myfile2 << s26 ; - myfile2.close(); -} - - -void setSteeringParams(ros::NodeHandle &n){ - std::ofstream myfile2; - - myfile2.open(data_path+"hmmwv/steering/HMMWV_RackPinion.json",std::ofstream::out | std::ofstream::trunc); // Yes - std::string s1 = "{"; - std::string s2 = " \"Name\": \"HMMWV Rack-Pinion Steering\","; - std::string s3 = " \"Type\": \"Steering\","; - std::string s4 = " \"Template\": \"RackPinion\","; - std::string s5 = " \"Steering Link\":"; - std::string s6 = " {"; - std::string s7 = " \"Mass\": "; - std::string s8 ; - n.getParam("/vehicle/chrono/vehicle_params/steeringLinkMass", s8); - std::string s9 = " \"COM\": 0,"; - std::string s10 = " \"Inertia\": "; - std::string s11; - n.getParam("/vehicle/chrono/vehicle_params/steeringLinkInertia",s11); - std::string s12 = " \"Radius\": "; - std::string s13; - n.getParam("/vehicle/chrono/vehicle_params/steeringLinkRadius",s13); - std::string s14 = " \"Length\": "; - std::string s15; - n.getParam("/vehicle/chrono/vehicle_params/steeringLinkLength",s15); - std::string s16 = " },"; - std::string s17 = " \"Pinion\":"; - std::string s18 = " \"Radius\": "; - std::string s19; - n.getParam("/vehicle/chrono/vehicle_params/pinionRadius",s19); - std::string s20 = " \"Maximum Angle\": "; - std::string s21; - n.getParam("/vehicle/chrono/vehicle_params/pinionMaxAngle",s21); - std::string s22 = " }"; - std::string s23 = "}"; - - - - myfile2 << s1 << '\n'; - myfile2 << s2 << '\n'; - myfile2 << s3 << '\n'; - myfile2 << s4 << '\n'; - myfile2 << '\n'; - myfile2 << s5 << '\n'; - myfile2 << s6 << '\n'; - myfile2 << s7 << s8 << '\n'; - myfile2 << s9 << '\n'; - myfile2 << s10 << s11 << '\n'; - myfile2 << s12 << s13 << '\n'; - myfile2 << s14 << s15 << '\n'; - myfile2 << s16 << '\n'; - myfile2 << '\n'; - myfile2 << s17 << '\n'; - myfile2 << s18 << s19 << '\n'; - myfile2 << s20 << '\n'; - myfile2 << s21 << s21 << '\n'; - myfile2 << s22 << '\n'; - myfile2 << s23 << '\n'; - - myfile2.close(); -} - -void setBrakingParams(ros::NodeHandle &n){ - std::ofstream myfile2; - std::ofstream myfile3; - - std::string s1 = "{ "; - std::string s2 = " \"Name\": \"HMMWV Brake Front\","; - std::string s3 = " \"Type\": \"Brake\","; - std::string s4 = " \"Template\": \"BrakeSimple\","; - std::string s5 = " \"Maximum Torque\": "; - std::string s6; - n.getParam("vehicle/chrono/vehicle_params/maxBrakeTorque",s6); - std::string s7 = "}"; - std::string s8 = " \"Name\": \"HMMWV Brake Rear\","; - - myfile2.open(data_path+"hmmwv/brake/HMMWV_BrakeSimple_Front.json",std::ofstream::out | std::ofstream::trunc); // Yes - myfile2 << s1 << '\n'; - myfile2 << s2 << '\n'; - myfile2 << s3 << '\n'; - myfile2 << s4 << '\n'; - myfile2 << '\n'; - myfile2 << s5 << s6 << '\n'; - myfile2 << s7 << '\n'; - myfile2.close(); - - myfile3.open(data_path+"hmmwv/brake/HMMWV_BrakeSimple_Rear.json",std::ofstream::out | std::ofstream::trunc); // Yes - myfile3 << s1 << '\n'; - myfile3 << s8 << '\n'; - myfile3 << s2 << '\n'; - myfile3 << s3 << '\n'; - myfile3 << s4 << '\n'; - myfile3 << '\n'; - myfile3 << s5 << s6 << '\n'; - myfile3 << s7 << '\n'; - myfile3.close(); -} - -void controlCallback(const nloptcontrol_planner::Trajectory::ConstPtr& control_msg){ - traj_t = control_msg->t; - traj_sa = control_msg->sa; - traj_ux = control_msg->ux; - - /* - std::cout << "Current time: "<< time << std::endl; - std::cout << "Time trajectory: " << " "; - for(int i = 0; i < traj_t.size(); i++) - std::cout << traj_t[i] << " "; - std::cout << std::endl; - - std::cout << "Speed trajectory: " << " "; - for(int i = 0; i < traj_ux.size(); i++) - std::cout << traj_ux[i] << " "; - std::cout << std::endl; - - std::cout << "Steering trajectory: " << " "; - for(int i = 0; i < traj_sa.size(); i++) - std::cout << traj_sa[i] << " "; - std::cout << std::endl; -*/ - std::cout << "Target_speed: " << target_speed_interp << " Actual speed: " << speed << std::endl; - // std::cout << "Target_steering: " << target_steering_interp << " Actual steering: " << target_steering_interp << std::endl; - // std::cout << std::endl; -} - -// ============================================================================= -int main(int argc, char* argv[]) { - - //unsigned int microseconds = 10000000; - //std::cout << "Sleeping for ten sec..." << std::endl; - //usleep(microseconds); - - char cwd[1024]; - if (getcwd(cwd, sizeof(cwd)) != NULL) - fprintf(stdout, "Current working dir: %s\n", cwd); - else - perror("getcwd() error"); - GetLog() << "Copyright (c) 2017 projectchrono.org\nChrono version: " << CHRONO_VERSION << "\n\n"; - - - //fprintf(stdout, "CHRONO_DATA_DIR: %s\n", CHRONO_DATA_DIR); - SetChronoDataPath(CHRONO_DATA_DIR); - //SetChronoDataPath(chrono_data); - vehicle::SetDataPath(data_path); - - // read maximum_steering_angle from json - std::string filename(data_path + "hmmwv/steering/HMMWV_PitmanArm.json"); // Yes - FILE* fp = fopen(filename.c_str(), "r"); - char readBuffer[65536]; - FileReadStream is(fp, readBuffer, sizeof(readBuffer)); - fclose(fp); - Document d; - d.ParseStream(is); - maximum_steering_angle = d["Revolute Joint"]["Maximum Angle"].GetDouble(); - - ros::init(argc, argv, "Traj_follower"); - ros::NodeHandle n; - n.setParam("system/chrono/flags/initialized",true); - n.getParam("system/params/step_size",step_size); - - bool planner_init; - // bool planner_init2; - - std::string planner_namespace; - n.getParam("system/planner",planner_namespace); - n.getParam("system/"+planner_namespace+"/flags/initialized",planner_init); - std::cout << "The planner state:" << planner_init << std::endl; - ros::Subscriber sub = n.subscribe(planner_namespace+"/control", 100, controlCallback); - - //planner_init2=planner_init1; - // n.getParam("system/"+planner_namespace+"/flags/initialized",planner_init2); - - if(!planner_init){ - waitForLoaded(n); - } - //std::string planner_init; - - n.getParam("system/"+planner_namespace+"/flags/initialized",planner_init); - - // Desired vehicle speed (m/s) - double target_speed; - n.getParam("state/chrono/X0/v_des",target_speed); - - //Initial Position - double x0, y0, z0, yaw0, pitch0, roll0, goal_x, goal_y;; - bool gui_switch; - n.getParam("case/actual/X0/x",x0); - n.getParam("case/actual/X0/yVal",y0); - n.getParam("state/chrono/X0/z",z0); - n.getParam("case/actual/X0/psi",yaw0); - n.getParam("state/chrono/X0/theta",pitch0); - n.getParam("state/chrono/X0/phi",roll0); - n.getParam("case/goal/x",goal_x); - n.getParam("case/goal/yVal",goal_y); - - n.getParam("system/chrono/flags/gui",gui_switch); - - bool goal_attained = false; - bool running = true; - - setSteeringParams(n); - setDrivelineParams(n); - setBrakingParams(n); - setChassisParams(n); - ChVector<> initLoc(x0, y0, z0); -// ChQuaternion<> initRot(q[0],q[1],q[2],q[3]); - - double t0 = std::cos(yaw0 * 0.5f); - double t1 = std::sin(yaw0 * 0.5f); - double t2 = std::cos(roll0 * 0.5f); - double t3 = std::sin(roll0 * 0.5f); - double t4 = std::cos(pitch0 * 0.5f); - double t5 = std::sin(pitch0 * 0.5f); - - double q0_0 = t0 * t2 * t4 + t1 * t3 * t5; - double q0_1 = t0 * t3 * t4 - t1 * t2 * t5; - double q0_2 = t0 * t2 * t5 + t1 * t3 * t4; - double q0_3 = t1 * t2 * t4 - t0 * t3 * t5; - - ChQuaternion<> initRot(q0_0,q0_1,q0_2,q0_3); - //ChQuaternion<> initRot(cos(PI/4), 0, 0, sin(PI/4)); //initial yaw of pi/2 - - ros::Publisher vehicleinfo_pub = n.advertise("vehicleinfo", 1); - - //ros::Rate loop_rate(5); - - // ------------------------------ - // Create the vehicle and terrain - // ------------------------------ - - // Create the HMMWV vehicle, set parameters, and initialize - std::cout << "Start reading the file" << std::endl; - WheeledVehicle my_hmmwv(data_path + "hmmwv/vehicle/HMMWV_Vehicle.json",contact_method); // Yes - my_hmmwv.Initialize(ChCoordsys<>(initLoc, initRot),0.0); - - std::cout << "Successfully read the file" << std::endl; - my_hmmwv.SetChassisVehicleCollide(false); - my_hmmwv.GetChassis()->SetVisualizationType(chassis_vis_type); -// my_hmmwv.GetChassis()->AddVisualizationAssets(chassis_vis_type); - - my_hmmwv.SetSuspensionVisualizationType(suspension_vis_type); - my_hmmwv.SetSteeringVisualizationType(steering_vis_type); - my_hmmwv.SetWheelVisualizationType(wheel_vis_type); - //my_hmmwv.SetTireVisualizationType(tire_vis_type); - RigidTire tire_front_left(rigid_tire_file); - RigidTire tire_front_right(rigid_tire_file); - RigidTire tire_rear_left(rigid_tire_file); - RigidTire tire_rear_right(rigid_tire_file); - - - TerrainForces tire_forces(4); - - tire_front_left.Initialize(my_hmmwv.GetWheelBody(0), LEFT); - tire_front_right.Initialize(my_hmmwv.GetWheelBody(1), LEFT); - tire_rear_left.Initialize(my_hmmwv.GetWheelBody(2), RIGHT); - tire_rear_right.Initialize(my_hmmwv.GetWheelBody(3), RIGHT); - - - tire_front_left.SetVisualizationType(tire_vis_type); - tire_front_right.SetVisualizationType(tire_vis_type); - tire_rear_left.SetVisualizationType(tire_vis_type); - tire_rear_right.SetVisualizationType(tire_vis_type); - - // Create the terrain - float frict_coeff, rest_coeff; - n.getParam("vehicle/common/frict_coeff",frict_coeff); - n.getParam("vehicle/common/rest_coeff",rest_coeff); - - RigidTerrain terrain(my_hmmwv.GetSystem()); - my_hmmwv.GetWheel(0)->SetContactFrictionCoefficient(frict_coeff); - my_hmmwv.GetWheel(0)->SetContactRestitutionCoefficient(rest_coeff); - - - /*change: 10/11/2018 */ - auto patch1 = terrain.AddPatch(ChCoordsys<>(ChVector<>(0, 0, -5), QUNIT), ChVector<>(20,20, 10)); - patch1->SetContactFrictionCoefficient(0.9f); // - patch1->SetContactRestitutionCoefficient(0.01f); // - patch1->SetContactMaterialProperties(2e7f, 0.3f); // - patch1->SetColor(ChColor(0.8f, 0.8f, 0.5f)); // - patch1->SetTexture(data_path+"terrain/textures/tile4.jpg", 200, 200); - - terrain.Initialize(); - /* - //terrain.SetContactFrictionCoefficient(0.9f); - //terrain.SetContactRestitutionCoefficient(0.01f); - terrain.SetContactMaterialProperties(2e7f, 0.3f); - terrain.SetColor(ChColor(1, 1, 1)); - //terrain.SetTexture(chrono::vehicle::GetDataFile("terrain/textures/tile4.jpg"), 200, 200); - terrain.SetTexture(data_path+"terrain/textures/tile4.jpg", 200, 200); - terrain.Initialize(terrainHeight, terrainLength, terrainWidth);*/ - /*end_change*/ - - - SimplePowertrain powertrain(vehicle::GetDataFile(data_path + "hmmwv/powertrain/HMMWV_SimplePowertrain.json")); // Yes - // HMMWV_Powertrain powertrain; - //powertrain.Initialize(my_hmmwv.GetChassisBody(),my_hmmwv.GetDriveshaft()); - //SimplePowertrain powertrain(vehicle::GetDataFile(simplepowertrain_file)); - powertrain.Initialize(my_hmmwv.GetChassisBody(), my_hmmwv.GetDriveshaft()); - //std::vector GearRatios; - //n.getParam("vehicle/chrono/vehicle_params/gearRatios",GearRatios); - //powertrain.SetGearRatios(GearRatios); - - // --------------------------------------- - // Create the vehicle Irrlicht application - // --------------------------------------- - - ChVehicleIrrApp app(&my_hmmwv, &powertrain, L"Steering Controller Demo", - irr::core::dimension2d(800, 640)); - - app.SetHUDLocation(500, 20); - app.SetSkyBox(); - app.AddTypicalLogo(); - app.AddTypicalLights(irr::core::vector3df(-150.f, -150.f, 200.f), irr::core::vector3df(-150.f, 150.f, 200.f), 100, - 100); - app.AddTypicalLights(irr::core::vector3df(150.f, -150.f, 200.f), irr::core::vector3df(150.0f, 150.f, 200.f), 100, - 100); - app.EnableGrid(false); - app.SetChaseCamera(trackPoint, 6.0, 0.5); - - app.SetTimestep(step_size); - app.SetTryRealtime(true); - - // ------------------------- - // Create the driver systems - // ------------------------- - - // Create both a GUI driver and a path-follower and allow switching between them - ChIrrGuiDriver driver_gui(app); - driver_gui.Initialize(); - - // --------------- - // Simulation loop - // --------------- - - // Driver location in vehicle local frame - ChVector<> driver_pos = my_hmmwv.GetChassis()->GetLocalDriverCoordsys().pos; - // Number of simulation steps between miscellaneous events - double render_step_size = 1 / fps; - int render_steps = (int)std::ceil(render_step_size / step_size); - double debug_step_size = 1 / debug_fps; - int debug_steps = (int)std::ceil(debug_step_size / step_size); - - // Initialize simulation frame counter and simulation time - ChRealtimeStepTimer realtime_timer; - int sim_frame = 0; - int render_frame = 0; - - double throttle_input, steering_input, braking_input; - std::vector x_traj_curr, y_traj_curr,x_traj_prev,y_traj_prev; //Initialize xy trajectory vectors - parameters hmmwv_params{terrain,tire_forces,my_hmmwv,realtime_timer,sim_frame,steering_input,throttle_input,braking_input,x_traj_curr,y_traj_curr,x_traj_prev,y_traj_prev,target_speed,render_steps,render_frame}; - //Load xy parameters for the first timestep - // std::string planner_namespace; - // n.getParam("system/planner",planner_namespace); - - // ---------------------- - // Create the Bezier path - // ---------------------- - - // Create and register a custom Irrlicht event receiver to allow selecting the - // current driver model. - ChDriverSelector selector(my_hmmwv, &driver_gui); - app.SetUserEventReceiver(&selector); - - // Finalize construction of visualization assets - app.AssetBindAll(); - app.AssetUpdateAll(); - - // ----------------- - // Initialize output - // ----------------- - - state_output = state_output || povray_output; - - if (state_output) { - if (ChFileutils::MakeDirectory(out_dir.c_str()) < 0) { - std::cout << "Error creating directory " << out_dir << std::endl; - return 1; - } - } - -/* - utils::CSV_writer csv("\t"); - csv.stream().setf(std::ios::scientific | std::ios::showpos); - csv.stream().precision(6); -*/ - utils::ChRunningAverage fwd_acc_GC_filter(filter_window_size); - utils::ChRunningAverage lat_acc_GC_filter(filter_window_size); - - utils::ChRunningAverage fwd_acc_driver_filter(filter_window_size); - utils::ChRunningAverage lat_acc_driver_filter(filter_window_size); - - std::ofstream myfile1; - myfile1.open(data_path+"paths/position.txt",std::ofstream::out | std::ofstream::trunc); - //get mass and moment of inertia about z axis - n.setParam("vehicle/common/m",my_hmmwv.GetVehicleMass()); - const ChMatrix33<> inertia_mtx= my_hmmwv.GetChassisBody()->GetInertia(); - double Izz=inertia_mtx.GetElement(2,2); - n.setParam("vehicle/common/Izz",Izz); - // get distance to front and rear axles - // enum chrono::vehicle::VehicleSide LEFT; - // enum chrono::vehicle::VehicleSide RIGHT; - ChVector<> veh_com= my_hmmwv.GetVehicleCOMPos(); - ChVector<> la_pos=my_hmmwv.GetSuspension(0)->GetSpindlePos(chrono::vehicle::VehicleSide::RIGHT); - ChVector<> lb_pos=my_hmmwv.GetSuspension(0)->GetSpindlePos(chrono::vehicle::VehicleSide::LEFT); - double la_length, lb_length; - ChVector<> la_diff; - la_diff.Sub(veh_com,la_pos); - ChVector<> lb_diff; - lb_diff.Sub(veh_com,lb_pos); - la_length=la_diff.Length(); - lb_length=lb_diff.Length(); - n.setParam("vehicle/common/la",la_length); - n.setParam("vehicle/common/lb",lb_length); - - // get friction and restitution coefficients - // float frict_coeff, rest_coeff; - frict_coeff = my_hmmwv.GetWheel(0)->GetCoefficientFriction(); - rest_coeff = my_hmmwv.GetWheel(0)->GetCoefficientRestitution(); - n.setParam("vehicle/common/frict_coeff",frict_coeff); - n.setParam("vehicle/common/rest_coeff",rest_coeff); - - // set up the controller - double Kp, Ki, Kd, Kw; - std::string windup_method; - n.getParam("controller/Kp",Kp); - n.getParam("controller/Ki",Ki); - n.getParam("controller/Kd",Kd); - n.getParam("controller/Kw",Kw); - n.getParam("controller/anti_windup",windup_method); - n.getParam("controller/time_shift", time_shift); - - controller.set_PID(Kp, Ki, Kd, Kw); - controller.set_step_size(step_size); - controller.set_output_limit(-1.0, 1.0); - controller.set_windup_metohd(windup_method); - controller.initialize(); - ae_int_t natural_bound_type = 2; - - std::cout<< "Go into the loop..." << std::endl; - - while(n.ok()){ - while (running) { - if(gui_switch) app.GetDevice()->run(); - ros::spinOnce(); - n.setParam("system/chrono/flags/running",true); - - // ros::Subscriber sub = n.subscribe("desired_ref", 1, ¶meters::controlCallback, &hmmwv_params); - - // Render scene and output POV-Ray data - if (hmmwv_params.sim_frame % hmmwv_params.render_steps == 0 && gui_switch) { - - app.BeginScene(true, true, irr::video::SColor(255, 140, 161, 192)); - app.DrawAll(); - app.EndScene(); - - hmmwv_params.render_frame++; - } - - ros_chrono_msgs::veh_status data_out; - /* - ChVector<> acc_CG = my_hmmwv.GetVehicle().GetChassisBody()->GetPos_dtdt(); - ChVector<> acc_driver = my_hmmwv.GetVehicle().GetVehicleAcceleration(driver_pos); - double fwd_acc_CG = fwd_acc_GC_filter.Add(acc_CG.x()); - double lat_acc_CG = lat_acc_GC_filter.Add(acc_CG.y()); - double fwd_acc_driver = fwd_acc_driver_filter.Add(acc_driver.x()); - double lat_acc_driver = lat_acc_driver_filter.Add(acc_driver.y());*/ - double time = hmmwv_params.my_hmmwv.GetSystem()->GetChTime(); - - // End simulation - if (time >= t_end) - break; - - real_1d_array t_array; - real_1d_array steering_array; - real_1d_array speed_array; - - t_array.setcontent(traj_t); - steering_array.setcontent(traj_sa); - speed_array.setcontent(traj_ux); - spline1dinterpolant s_ux; - spline1dinterpolant s_sa; - spline1dbuildcubic(t_array, speed_array, s_ux); - target_speed_interp = spline1dcalc(s_ux, time + time_shift); - spline1dbuildcubic(t_array, steering_array, s_sa); - target_steering_interp = spline1dcalc(s_sa, time); - - double speed_error = target_speed_interp - speed; - controller_output = controller.control(speed_error); - - target_steering_interp = target_steering_interp / PI * 180.0 / maximum_steering_angle * 2; - - hmmwv_params.target_speed = target_speed_interp; - - // Hack for acceleration-braking maneuver - /* // on-off controller - bool braking = false; - if (my_hmmwv.GetVehicle().GetVehicleSpeed() > hmmwv_params.target_speed) - braking = true; - if (braking) { - hmmwv_params.throttle_input = 0; - hmmwv_params.braking_input = 1; - } - else { - hmmwv_params.throttle_input = 1; - hmmwv_params.braking_input = 0; - } - */ - // pid controller - if (controller_output > 0){ - hmmwv_params.throttle_input = controller_output; - hmmwv_params.braking_input = 0; - } - else{ - hmmwv_params.throttle_input = 0; - hmmwv_params.braking_input = -controller_output; - } - - // Hack for steering maneuver - hmmwv_params.steering_input = target_steering_interp; - - - // std::cout << "Chrono steering input: " << hmmwv_params.steering_input < global_pos = hmmwv_params.my_hmmwv.GetVehicleCOMPos();//global location of chassis reference frame origin - ChQuaternion<> global_orntn = hmmwv_params.my_hmmwv.GetVehicleRot();//global orientation as quaternion - ChVector<> rot_dt = hmmwv_params.my_hmmwv.GetChassisBody()->GetWvel_loc();//global orientation as quaternion - ChVector<> global_velCOM = hmmwv_params.my_hmmwv.GetChassisBody()->GetPos_dt(); - ChVector<> global_accCOM = hmmwv_params.my_hmmwv.GetChassisBody()->GetPos_dtdt(); - //ChVector<> euler_ang = global_orntn.Q_to_Rotv(); //convert to euler angles - //ChPacejkaTire<> slip_angle = GetSlipAngle() - double slip_angle = tire_front_left.GetLongitudinalSlip(); - speed = hmmwv_params.my_hmmwv.GetVehicleSpeedCOM(); - - double q0 = global_orntn[0]; - double q1 = global_orntn[1]; - double q2 = global_orntn[2]; - double q3 = global_orntn[3]; - - double yaw_val=atan2(2*(q0*q3+q1*q2),1-2*(q2*q2+q3*q3)); - double theta_val=asin(2*(q0*q2-q3*q1)); - double phi_val= atan2(2*(q0*q1+q2*q3),1-2*(q1*q1+q2*q2)); - - n.setParam("state/chrono/t",time); //time in chrono simulation - n.setParam("state/chrono/x", global_pos[0]) ; - n.setParam("state/chrono/yVal",global_pos[1]); - n.setParam("state/chrono/ux",fabs(global_velCOM[0])); //speed measured at the origin of the chassis reference frame. - n.setParam("state/chrono/v", global_velCOM[1]); - n.setParam("state/chrono/ax", global_accCOM[0]); - n.setParam("state/chrono/psi",yaw_val); //in radians - n.setParam("state/chrono/theta",theta_val); //in radians - n.setParam("state/chrono/phi",phi_val); //in radians - n.setParam("state/chrono/r",-rot_dt[2]);//yaw rate - n.setParam("state/chrono/sa",slip_angle); //slip angle - n.setParam("state/chrono/control/thr",hmmwv_params.throttle_input); //throttle input in the range [0,+1] - n.setParam("state/chrono/control/brk",hmmwv_params.braking_input); //braking input in the range [0,+1] - n.setParam("state/chrono/control/str",hmmwv_params.steering_input); //steeering input in the range [-1,+1] - - n.setParam("system/simulation_time", time); - - data_out.t_chrono=time; //time in chrono simulation - data_out.x_pos= global_pos[0]; - data_out.y_pos=global_pos[1]; - data_out.x_v= fabs(global_velCOM[0]); //speed measured at the origin of the chassis reference frame. - data_out.y_v= global_velCOM[1]; - data_out.x_a= global_accCOM[0]; - data_out.yaw_curr=yaw_val; //in radians - data_out.yaw_rate=-rot_dt[2];//yaw rate - data_out.sa=slip_angle; //slip angle - data_out.thrt_in=hmmwv_params.throttle_input; //throttle input in the range [0,+1] - data_out.brk_in=hmmwv_params.braking_input; //braking input in the range [0,+1] - data_out.str_in=hmmwv_params.steering_input; //steeering input in the range [-1,+1] - - vehicleinfo_pub.publish(data_out); - // loop_rate.sleep(); - - myfile1 << ' ' << global_pos[0] << ' '<< global_pos[1] <<' ' << global_pos[2] << '\n'; - n.getParam("system/" + planner_namespace + "/flags/goal_attained",goal_attained); - if(goal_attained){ - n.setParam("system/goal_attained","true"); - n.setParam("system/chrono/flags/running","false"); - running = false; - } - } - } -/* - if (state_output){ - csv.write_to_file(out_dir + "/state.out"); - }*/ -myfile1.close(); - - return 0; -} diff --git a/ros/src/models/chrono/ros_chrono/old/trajectory_follower2.cpp b/ros/src/models/chrono/ros_chrono/old/trajectory_follower2.cpp deleted file mode 100644 index a0ea1076..00000000 --- a/ros/src/models/chrono/ros_chrono/old/trajectory_follower2.cpp +++ /dev/null @@ -1,993 +0,0 @@ -// ============================================================================= -// PROJECT CHRONO - http://projectchrono.org -// -// Copyright (c) 2014 projectchrono.org -// All rights reserved. -// -// Use of this source code is governed by a BSD-style license that can be found -// in the LICENSE file at the top level of the distribution and at -// http://projectchrono.org/license-chrono.txt. -// -// ============================================================================= -// Authors: Radu Serban -// ============================================================================= -// -// Demonstration of a steering path-follower PID controller. -// -// The vehicle reference frame has Z up, X towards the front of the vehicle, and -// Y pointing to the left. -// TO DO: -// Find proper yaw rate calculation -// Subsscribe to msg from obstacle_avoidance_chrono, callback to that to calculate ChBezierCurve -// ============================================================================= - -#include -#include -#include "boost/bind.hpp" -#include "chrono/core/ChFileutils.h" -#include "chrono/core/ChRealtimeStep.h" -#include "chrono/utils/ChFilters.h" -#include -#include -#include "ros/ros.h" -#include "std_msgs/String.h" -#include "ros_chrono_msgs/veh_status.h" -#include "nloptcontrol_planner/Trajectory.h" -#include -#include -#include -#include -#include -#include -//#include "tf/tf.h" -#include -#include "chrono_vehicle/ChVehicleModelData.h" -#include "chrono_vehicle/terrain/RigidTerrain.h" -#include "chrono_vehicle/driver/ChIrrGuiDriver.h" -#include "chrono_vehicle/driver/ChPathFollowerDriver.h" -#include "chrono_vehicle/wheeled_vehicle/utils/ChWheeledVehicleIrrApp.h" -#include "chrono_models/vehicle/hmmwv/HMMWV.h" -#include "chrono/physics/ChSystem.h" -#include "chrono_vehicle/wheeled_vehicle/tire/ChPacejkaTire.h" -//#include "chrono_models/vehicle/hmmwv/HMMWV_Pac02Tire.h" -#include "chrono_vehicle/wheeled_vehicle/tire/RigidTire.h" -#include "chrono_vehicle/wheeled_vehicle/tire/LugreTire.h" -#include "chrono_models/vehicle/hmmwv/HMMWV_ReissnerTire.h" -#include "chrono_vehicle/ChSubsysDefs.h" -#include "chrono_vehicle/wheeled_vehicle/vehicle/WheeledVehicle.h" -#include "chrono_vehicle/powertrain/ChShaftsPowertrain.h" -#include "chrono_vehicle/powertrain/SimplePowertrain.h" -#include "chrono_thirdparty/rapidjson/document.h" -#include "chrono_thirdparty/rapidjson/filereadstream.h" - -#include "chrono/core/ChFileutils.h" -#include "chrono/core/ChStream.h" -#include "chrono/utils/ChFilters.h" -#include "chrono/utils/ChUtilsInputOutput.h" -#include "chrono/solver/ChSolverMINRES.h" -#include "chrono_vehicle/ChConfigVehicle.h" - -#define PI 3.1415926535 -//using veh_status.msg -using namespace chrono; -using namespace chrono::geometry; -using namespace chrono::vehicle; -using namespace chrono::vehicle::hmmwv; - -using namespace alglib; - -using namespace rapidjson; -// ============================================================================= -// Problem parameters -// Main Data Path -//std::string data_path("/home/shreyas/.julia/v0.6/MAVs/catkin_ws/data/vehicle/"); -std::string data_path("../../../src/models/chrono/ros_chrono/src/data/vehicle/"); -//std::string data_path("src/system/chrono/ros_chrono/src/data/vehicle/"); -// Contact method type -ChMaterialSurface::ContactMethod contact_method = ChMaterialSurface::NSC; - -// Type of tire model (RIGID, LUGRE, FIALA, or PACEJKA) -// TireModelType tire_model = TireModelType::RIGID; - -// Input file name for PACEJKA tires if they are selected -std::string pacejka_tire_file_left(data_path+"hmmwv/tire/HMMWV_pacejka_left.tir"); -std::string pacejka_tire_file_right(data_path+"hmmwv/tire/HMMWV_pacejka_right.tir"); -std::string lugre_tire_file(data_path+"hmmwv/tire/HMMWV_LugreTire.json"); -std::string rigid_tire_file(data_path+"hmmwv/tire/HMMWV_RigidTire.json"); -std::string reissner_tire_file(data_path+"hmmwv/tire/HMMWV_ReissnerTire.json"); -//std::string pacejka_tire_file("hmmwv/tire/HMMWV_pacejka.tir"); -// Type of powertrain model (SHAFTS or SIMPLE) -PowertrainModelType powertrain_model = PowertrainModelType::SHAFTS; - -// Drive type (FWD, RWD, or AWD) -DrivelineType drive_type = DrivelineType::RWD; - -// Visualization type for vehicle parts (PRIMITIVES, MESH, or NONE) -VisualizationType chassis_vis_type = VisualizationType::PRIMITIVES; -VisualizationType suspension_vis_type = VisualizationType::PRIMITIVES; -VisualizationType steering_vis_type = VisualizationType::PRIMITIVES; -VisualizationType wheel_vis_type = VisualizationType::NONE; -VisualizationType tire_vis_type = VisualizationType::PRIMITIVES; - -std::string path_file(data_path+"paths/my_path.txt"); -std::string simplepowertrain_file(data_path+"hmmwv/powertrain/HMMWV_ShaftsPowertrain.json"); -WheelState wheel_states[4]; - - -// Rigid terrain dimensions -double terrainHeight = 0; -double terrainLength = 500.0; // size in X direction -double terrainWidth = 500.0; // size in Y direction - -// Point on chassis tracked by the chase camera -ChVector<> trackPoint(0.0, 0.0, 1.75); - -// Simulation step size -double step_size = 1e-2; -double tire_step_size = step_size; - -// Simulation end time -double t_end = 1000; - -// Render FPS -double fps = 60; - -// Debug logging -bool debug_output = false; -double debug_fps = 10; - -// Output directories -const std::string out_dir = GetChronoOutputPath() + "STEERING_CONTROLLER"; -const std::string pov_dir = out_dir + "/POVRAY"; - -// POV-Ray output -bool povray_output = false; - -// Vehicle state output (forced to true if povray output enabled) -bool state_output = false; -int filter_window_size = 20; - -// In src/data/vehicle/hmmwv/steering/HMMWV_PitmanArm.json revolution joint -double speed = 0.0; -double maximum_steering_angle; -// Controller output -double target_steering_interp = 0.0; -double target_speed_interp = 0.0; -double controller_output = 0.0; -double time_shift = 0.0; -PID controller; -std::vector traj_t(2,0); -std::vector traj_sa(2,0); -std::vector traj_ux(2,0); - -// ============================================================================= - -// Custom Irrlicht event receiver for selecting current driver model. -class ChDriverSelector : public irr::IEventReceiver { - public: - ChDriverSelector(const ChVehicle& vehicle, ChIrrGuiDriver* driver_gui) - : m_vehicle(vehicle), - m_driver_gui(driver_gui), - m_driver(m_driver_gui), - m_using_gui(true) {} - - ChDriver* GetDriver() { return m_driver; } - bool UsingGUI() const { return m_using_gui; } - - virtual bool OnEvent(const irr::SEvent& event) { - return false; - } - - private: - bool m_using_gui; - const ChVehicle& m_vehicle; - ChIrrGuiDriver* m_driver_gui; - ChDriver* m_driver; -}; - -struct parameters -{ - RigidTerrain terrain; - TireForces tire_forces; - WheeledVehicle my_hmmwv; - ChRealtimeStepTimer realtime_timer; - int sim_frame; - double steering_input; - double throttle_input; - double braking_input; - std::vector x_traj_curr; - std::vector y_traj_curr; - std::vector x_traj_prev; - std::vector y_traj_prev; - double target_speed; - int render_steps; - int render_frame; -} ; - -void waitForLoaded(ros::NodeHandle &n){ - bool planner_init = false; - std::string planner_namespace; - n.getParam("system/planner",planner_namespace); - n.getParam("system/"+planner_namespace+"/flags/initialized",planner_init); - while(!planner_init){ - usleep(500); // < my question - n.getParam("system/"+planner_namespace+"/flags/initialized",planner_init); - - } - usleep(500); //sleep another 500ms to ensure everything is loaded. - //continue on here -} - -void setChassisParams(ros::NodeHandle &n){ - std::ofstream myfile2; - - myfile2.open(data_path+"hmmwv/chassis/HMMWV_Chassis.json",std::ofstream::out | std::ofstream::trunc); - std::string s1 = "{ "; - std::string s2 = " \"Name\": \"HMMWV chassis\","; - std::string s3 = " \"Type\": \"Chassis\","; - std::string s4 = " \"Template\": \"RigidChassis\","; - std::string s5 = " \"Components\":"; - std::string s6 = " ["; - std::string s7 = " {"; - std::string s8 = " \"Centroidal Frame\": {"; - std::string s9 = " \"Location\": "; - std::string s10; - n.getParam("vehicle/chrono/vehicle_params/centroidLoc",s10); - std::string s11 = " \"Orientation\": "; - std::string s12; - n.getParam("/vehicle/chrono/vehicle_params/centroidOrientation",s12); - std::string s13 = " },"; - std::string s14 = " \"Mass\": "; - std::string s15; - n.getParam("/vehicle/chrono/vehicle_params/chassisMass",s15); - std::string s16 = " \"Moments of Inertia\": "; - std::string s17; - n.getParam("/vehicle/chrono/vehicle_params/chassisInertia",s17); - std::string s18 = " \"Products of Inertia\": [0, 0, 0],"; - std::string s19 = " \"Void\": false"; - std::string s20 = " }"; - std::string s21 = " ],"; - std::string s22 = " \"Driver Position\":"; - std::string s23 = " {"; - std::string s24 = " \"Location\": "; - std::string s25; - n.getParam("/vehicle/chrono/vehicle_params/driverLoc",s25); - std::string s26 = " \"Orientation\": "; - std::string s27; - n.getParam("/vehicle/chrono/vehicle_params/driverOrientation",s27); - std::string s28 = " },"; - std::string s29 = " \"Visualization\":"; - std::string s30 = " {"; - std::string s31 = " \"Mesh\":"; - std::string s32 = " {"; - std::string s33 = " \"Filename\": \"hmmwv/hmmwv_chassis.obj\","; - std::string s34 = " \"Name\": \"hmmwv_chassis_POV_geom\""; - std::string s35 = " }"; - std::string s36 = " }"; - std::string s37 = "}"; - myfile2 << s1 << '\n'; - myfile2 << s2 << '\n'; - myfile2 << s3 << '\n'; - myfile2 << s4 << '\n'; - myfile2 << '\n'; - myfile2 << s5 << '\n'; - myfile2 << s6 << '\n'; - myfile2 << s7 << '\n'; - myfile2 << s8 << '\n'; - myfile2 << s9 << s10 << '\n'; - myfile2 << s11 << s12 << '\n'; - myfile2 << s13 << '\n'; - myfile2 << s14 << s15 <<'\n'; - myfile2 << s16 << s17 << '\n'; - myfile2 << s18 << '\n'; - myfile2 << s19 << '\n'; - myfile2 << s20 << '\n'; - myfile2 << s21 << '\n'; - myfile2 << s22 << '\n'; - myfile2 << s23 << '\n'; - myfile2 << s24 << s25 << '\n'; - myfile2 << s26 << s27 << '\n'; - myfile2 << s28 << '\n'; - myfile2 << '\n'; - myfile2 << s29 << '\n'; - myfile2 << s30 << '\n'; - myfile2 << s31 << '\n'; - myfile2 << s32 << '\n'; - myfile2 << s33 << '\n'; - myfile2 << s34 << '\n'; - myfile2 << s35 << '\n'; - myfile2 << s36 << '\n'; - myfile2 << s37 << '\n'; - myfile2.close(); -} - -void setDrivelineParams(ros::NodeHandle &n){ - std::ofstream myfile2; - - myfile2.open(data_path+"hmmwv/driveline/HMMWV_Driveline2WD.json",std::ofstream::out | std::ofstream::trunc); - std::string s1 = "{ "; - std::string s2 = " \"Name\": \"HMMWV RWD Driveline\","; - std::string s3 = " \"Type\": \"Driveline\","; - std::string s4 = " \"Template\": \"ShaftsDriveline2WD\","; - std::string s5 = " \"Shaft Direction\":"; - std::string s6 = " {"; - std::string s7 = " \"Motor Block\": "; - std::string s8; - n.getParam("/vehicle/chrono/vehicle_params/motorBlockDirection",s8); - std::string s9 = " \"Axle\": "; - std::string s10; - n.getParam("/vehicle/chrono/vehicle_params/axleDirection",s10); - std::string s11 = " },"; - std::string s12 = " \"Shaft Inertia\":"; - std::string s13 = " {"; - std::string s14 = " \"Driveshaft\": "; - std::string s15; - n.getParam("/vehicle/chrono/vehicle_params/driveshaftInertia", s15); - std::string s16 = " \"Differential Box\": "; - std::string s17; - n.getParam("/vehicle/chrono/vehicle_params/differentialBoxInertia",s17); - std::string s18 = " },"; - std::string s19 = " \"Gear Ratio\":"; - std::string s20 = " {"; - std::string s21 = " \"Conical Gear\": "; - std::string s22; - n.getParam("/vehicle/chrono/vehicle_params/conicalGearRatio",s22); - std::string s23 = " \"Differential\": "; - std::string s24; - n.getParam("/vehicle/chrono/vehicle_params/differentialRatio",s24); - std::string s25 = " }"; - std::string s26 = "}"; - - myfile2 << s1 << '\n'; - myfile2 << s2 << '\n'; - myfile2 << s3 << '\n'; - myfile2 << s4 << '\n'; - myfile2 << '\n'; - myfile2 << s5 << '\n'; - myfile2 << s6 << '\n'; - myfile2 << s7 << s8 << '\n'; - myfile2 << s9 << s10 << '\n'; - myfile2 << s11 << '\n'; - myfile2 << '\n'; - myfile2 << s12 << '\n'; - myfile2 << s13 << '\n'; - myfile2 << s14 << s15 << '\n'; - myfile2 << s16 << s17 << '\n'; - myfile2 << s18 << '\n'; - myfile2 << '\n'; - myfile2 << s19 << '\n'; - myfile2 << s20 << '\n'; - myfile2 << s21 << s22 << '\n'; - myfile2 << s23 << s24 << '\n'; - myfile2 << s25 << '\n'; - myfile2 << s26 ; - myfile2.close(); -} - - -void setSteeringParams(ros::NodeHandle &n){ - std::ofstream myfile2; - - myfile2.open(data_path+"hmmwv/steering/HMMWV_RackPinion.json",std::ofstream::out | std::ofstream::trunc); - std::string s1 = "{"; - std::string s2 = " \"Name\": \"HMMWV Rack-Pinion Steering\","; - std::string s3 = " \"Type\": \"Steering\","; - std::string s4 = " \"Template\": \"RackPinion\","; - std::string s5 = " \"Steering Link\":"; - std::string s6 = " {"; - std::string s7 = " \"Mass\": "; - std::string s8 ; - n.getParam("/vehicle/chrono/vehicle_params/steeringLinkMass", s8); - std::string s9 = " \"COM\": 0,"; - std::string s10 = " \"Inertia\": "; - std::string s11; - n.getParam("/vehicle/chrono/vehicle_params/steeringLinkInertia",s11); - std::string s12 = " \"Radius\": "; - std::string s13; - n.getParam("/vehicle/chrono/vehicle_params/steeringLinkRadius",s13); - std::string s14 = " \"Length\": "; - std::string s15; - n.getParam("/vehicle/chrono/vehicle_params/steeringLinkLength",s15); - std::string s16 = " },"; - std::string s17 = " \"Pinion\":"; - std::string s18 = " \"Radius\": "; - std::string s19; - n.getParam("/vehicle/chrono/vehicle_params/pinionRadius",s19); - std::string s20 = " \"Maximum Angle\": "; - std::string s21; - n.getParam("/vehicle/chrono/vehicle_params/pinionMaxAngle",s21); - std::string s22 = " }"; - std::string s23 = "}"; - - - - myfile2 << s1 << '\n'; - myfile2 << s2 << '\n'; - myfile2 << s3 << '\n'; - myfile2 << s4 << '\n'; - myfile2 << '\n'; - myfile2 << s5 << '\n'; - myfile2 << s6 << '\n'; - myfile2 << s7 << s8 << '\n'; - myfile2 << s9 << '\n'; - myfile2 << s10 << s11 << '\n'; - myfile2 << s12 << s13 << '\n'; - myfile2 << s14 << s15 << '\n'; - myfile2 << s16 << '\n'; - myfile2 << '\n'; - myfile2 << s17 << '\n'; - myfile2 << s18 << s19 << '\n'; - myfile2 << s20 << '\n'; - myfile2 << s21 << s21 << '\n'; - myfile2 << s22 << '\n'; - myfile2 << s23 << '\n'; - - myfile2.close(); -} - -void setBrakingParams(ros::NodeHandle &n){ - std::ofstream myfile2; - std::ofstream myfile3; - - std::string s1 = "{ "; - std::string s2 = " \"Name\": \"HMMWV Brake Front\","; - std::string s3 = " \"Type\": \"Brake\","; - std::string s4 = " \"Template\": \"BrakeSimple\","; - std::string s5 = " \"Maximum Torque\": "; - std::string s6; - n.getParam("vehicle/chrono/vehicle_params/maxBrakeTorque",s6); - std::string s7 = "}"; - std::string s8 = " \"Name\": \"HMMWV Brake Rear\","; - - myfile2.open(data_path+"hmmwv/brake/HMMWV_BrakeSimple_Front.json",std::ofstream::out | std::ofstream::trunc); - myfile2 << s1 << '\n'; - myfile2 << s2 << '\n'; - myfile2 << s3 << '\n'; - myfile2 << s4 << '\n'; - myfile2 << '\n'; - myfile2 << s5 << s6 << '\n'; - myfile2 << s7 << '\n'; - myfile2.close(); - - myfile3.open(data_path+"hmmwv/brake/HMMWV_BrakeSimple_Rear.json",std::ofstream::out | std::ofstream::trunc); - myfile3 << s1 << '\n'; - myfile3 << s8 << '\n'; - myfile3 << s2 << '\n'; - myfile3 << s3 << '\n'; - myfile3 << s4 << '\n'; - myfile3 << '\n'; - myfile3 << s5 << s6 << '\n'; - myfile3 << s7 << '\n'; - myfile3.close(); -} - -void controlCallback(const nloptcontrol_planner::Trajectory::ConstPtr& control_msg){ - traj_t = control_msg->t; - traj_sa = control_msg->sa; - traj_ux = control_msg->ux; - - /* - std::cout << "Current time: "<< time << std::endl; - std::cout << "Time trajectory: " << " "; - for(int i = 0; i < traj_t.size(); i++) - std::cout << traj_t[i] << " "; - std::cout << std::endl; - - std::cout << "Speed trajectory: " << " "; - for(int i = 0; i < traj_ux.size(); i++) - std::cout << traj_ux[i] << " "; - std::cout << std::endl; - - std::cout << "Steering trajectory: " << " "; - for(int i = 0; i < traj_sa.size(); i++) - std::cout << traj_sa[i] << " "; - std::cout << std::endl; -*/ - std::cout << "Target_speed: " << target_speed_interp << " Actual speed: " << speed << std::endl; - // std::cout << "Target_steering: " << target_steering_interp << " Actual steering: " << target_steering_interp << std::endl; - // std::cout << std::endl; -} - -// ============================================================================= -int main(int argc, char* argv[]) { - - //unsigned int microseconds = 10000000; - //std::cout << "Sleeping for ten sec..." << std::endl; - //usleep(microseconds); - - char cwd[1024]; - if (getcwd(cwd, sizeof(cwd)) != NULL) - fprintf(stdout, "Current working dir: %s\n", cwd); - else - perror("getcwd() error"); - GetLog() << "Copyright (c) 2017 projectchrono.org\nChrono version: " << CHRONO_VERSION << "\n\n"; - - SetChronoDataPath(CHRONO_DATA_DIR); - vehicle::SetDataPath(data_path); - - // read maximum_steering_angle from json - std::string filename(data_path + "hmmwv/steering/HMMWV_PitmanArm.json"); - FILE* fp = fopen(filename.c_str(), "r"); - char readBuffer[65536]; - FileReadStream is(fp, readBuffer, sizeof(readBuffer)); - fclose(fp); - Document d; - d.ParseStream(is); - maximum_steering_angle = d["Revolute Joint"]["Maximum Angle"].GetDouble(); - - ros::init(argc, argv, "Traj_follower"); - ros::NodeHandle n; - n.setParam("system/chrono/flags/initialized",true); - n.getParam("system/params/step_size",step_size); - - bool planner_init; - // bool planner_init2; - - std::string planner_namespace; - n.getParam("system/planner",planner_namespace); - n.getParam("system/"+planner_namespace+"/flags/initialized",planner_init); - std::cout << "The planner state:" << planner_init << std::endl; - ros::Subscriber sub = n.subscribe(planner_namespace+"/control", 100, controlCallback); - - //planner_init2=planner_init1; - // n.getParam("system/"+planner_namespace+"/flags/initialized",planner_init2); - - if(!planner_init){ - waitForLoaded(n); - } - //std::string planner_init; - - n.getParam("system/"+planner_namespace+"/flags/initialized",planner_init); - - // Desired vehicle speed (m/s) - double target_speed; - n.getParam("state/chrono/X0/v_des",target_speed); - - //Initial Position - double x0, y0, z0, yaw0, pitch0, roll0, goal_x, goal_y;; - bool gui_switch; - n.getParam("case/actual/X0/x",x0); - n.getParam("case/actual/X0/yVal",y0); - n.getParam("state/chrono/X0/z",z0); - n.getParam("case/actual/X0/psi",yaw0); - n.getParam("state/chrono/X0/theta",pitch0); - n.getParam("state/chrono/X0/phi",roll0); - n.getParam("case/goal/x",goal_x); - n.getParam("case/goal/yVal",goal_y); - - n.getParam("system/chrono/flags/gui",gui_switch); - - bool goal_attained = false; - bool running = true; - - setSteeringParams(n); - setDrivelineParams(n); - setBrakingParams(n); - setChassisParams(n); - ChVector<> initLoc(x0, y0, z0); -// ChQuaternion<> initRot(q[0],q[1],q[2],q[3]); - - double t0 = std::cos(yaw0 * 0.5f); - double t1 = std::sin(yaw0 * 0.5f); - double t2 = std::cos(roll0 * 0.5f); - double t3 = std::sin(roll0 * 0.5f); - double t4 = std::cos(pitch0 * 0.5f); - double t5 = std::sin(pitch0 * 0.5f); - - double q0_0 = t0 * t2 * t4 + t1 * t3 * t5; - double q0_1 = t0 * t3 * t4 - t1 * t2 * t5; - double q0_2 = t0 * t2 * t5 + t1 * t3 * t4; - double q0_3 = t1 * t2 * t4 - t0 * t3 * t5; - - ChQuaternion<> initRot(q0_0,q0_1,q0_2,q0_3); - //ChQuaternion<> initRot(cos(PI/4), 0, 0, sin(PI/4)); //initial yaw of pi/2 - - ros::Publisher vehicleinfo_pub = n.advertise("vehicleinfo", 1); - - //ros::Rate loop_rate(5); - - // ------------------------------ - // Create the vehicle and terrain - // ------------------------------ - - // Create the HMMWV vehicle, set parameters, and initialize - std::cout << "Start reading the file" << std::endl; - WheeledVehicle my_hmmwv(data_path + "hmmwv/vehicle/HMMWV_Vehicle.json",contact_method); - my_hmmwv.Initialize(ChCoordsys<>(initLoc, initRot),0.0); - - std::cout << "Successfully read the file" << std::endl; - my_hmmwv.SetChassisVehicleCollide(false); - my_hmmwv.GetChassis()->SetVisualizationType(chassis_vis_type); -// my_hmmwv.GetChassis()->AddVisualizationAssets(chassis_vis_type); - - my_hmmwv.SetSuspensionVisualizationType(suspension_vis_type); - my_hmmwv.SetSteeringVisualizationType(steering_vis_type); - my_hmmwv.SetWheelVisualizationType(wheel_vis_type); - //my_hmmwv.SetTireVisualizationType(tire_vis_type); - RigidTire tire_front_left(rigid_tire_file); - RigidTire tire_front_right(rigid_tire_file); - RigidTire tire_rear_left(rigid_tire_file); - RigidTire tire_rear_right(rigid_tire_file); - - - TireForces tire_forces(4); - - tire_front_left.Initialize(my_hmmwv.GetWheelBody(0), LEFT); - tire_front_right.Initialize(my_hmmwv.GetWheelBody(1), LEFT); - tire_rear_left.Initialize(my_hmmwv.GetWheelBody(2), RIGHT); - tire_rear_right.Initialize(my_hmmwv.GetWheelBody(3), RIGHT); - - - tire_front_left.SetVisualizationType(tire_vis_type); - tire_front_right.SetVisualizationType(tire_vis_type); - tire_rear_left.SetVisualizationType(tire_vis_type); - tire_rear_right.SetVisualizationType(tire_vis_type); - - // Create the terrain - float frict_coeff, rest_coeff; - n.getParam("vehicle/common/frict_coeff",frict_coeff); - n.getParam("vehicle/common/rest_coeff",rest_coeff); - - RigidTerrain terrain(my_hmmwv.GetSystem()); - my_hmmwv.GetWheel(0)->SetContactFrictionCoefficient(frict_coeff); - my_hmmwv.GetWheel(0)->SetContactRestitutionCoefficient(rest_coeff); - - //terrain.SetContactFrictionCoefficient(0.9f); - //terrain.SetContactRestitutionCoefficient(0.01f); - terrain.SetContactMaterialProperties(2e7f, 0.3f); - terrain.SetColor(ChColor(1, 1, 1)); - //terrain.SetTexture(chrono::vehicle::GetDataFile("terrain/textures/tile4.jpg"), 200, 200); - terrain.SetTexture(data_path+"terrain/textures/tile4.jpg", 200, 200); - terrain.Initialize(terrainHeight, terrainLength, terrainWidth); - - //SimplePowertrain powertrain(vehicle::GetDataFile("hmmwv/powertrain/HMMWV_SimplePowertrain.json")); - HMMWV_Powertrain powertrain; - powertrain.Initialize(my_hmmwv.GetChassisBody(),my_hmmwv.GetDriveshaft()); - std::vector GearRatios; - n.getParam("vehicle/chrono/vehicle_params/gearRatios",GearRatios); - powertrain.SetGearRatios(GearRatios); - // --------------------------------------- - // Create the vehicle Irrlicht application - // --------------------------------------- - - ChVehicleIrrApp app(&my_hmmwv, &powertrain, L"Steering Controller Demo", - irr::core::dimension2d(800, 640)); - - app.SetHUDLocation(500, 20); - app.SetSkyBox(); - app.AddTypicalLogo(); - app.AddTypicalLights(irr::core::vector3df(-150.f, -150.f, 200.f), irr::core::vector3df(-150.f, 150.f, 200.f), 100, - 100); - app.AddTypicalLights(irr::core::vector3df(150.f, -150.f, 200.f), irr::core::vector3df(150.0f, 150.f, 200.f), 100, - 100); - app.EnableGrid(false); - app.SetChaseCamera(trackPoint, 6.0, 0.5); - - app.SetTimestep(step_size); - app.SetTryRealtime(true); - - // ------------------------- - // Create the driver systems - // ------------------------- - - // Create both a GUI driver and a path-follower and allow switching between them - ChIrrGuiDriver driver_gui(app); - driver_gui.Initialize(); - - // --------------- - // Simulation loop - // --------------- - - // Driver location in vehicle local frame - ChVector<> driver_pos = my_hmmwv.GetChassis()->GetLocalDriverCoordsys().pos; - // Number of simulation steps between miscellaneous events - double render_step_size = 1 / fps; - int render_steps = (int)std::ceil(render_step_size / step_size); - double debug_step_size = 1 / debug_fps; - int debug_steps = (int)std::ceil(debug_step_size / step_size); - - // Initialize simulation frame counter and simulation time - ChRealtimeStepTimer realtime_timer; - int sim_frame = 0; - int render_frame = 0; - - double throttle_input, steering_input, braking_input; - std::vector x_traj_curr, y_traj_curr,x_traj_prev,y_traj_prev; //Initialize xy trajectory vectors - parameters hmmwv_params{terrain,tire_forces,my_hmmwv,realtime_timer,sim_frame,steering_input,throttle_input,braking_input,x_traj_curr,y_traj_curr,x_traj_prev,y_traj_prev,target_speed,render_steps,render_frame}; - //Load xy parameters for the first timestep - // std::string planner_namespace; - // n.getParam("system/planner",planner_namespace); - - // ---------------------- - // Create the Bezier path - // ---------------------- - - // Create and register a custom Irrlicht event receiver to allow selecting the - // current driver model. - ChDriverSelector selector(my_hmmwv, &driver_gui); - app.SetUserEventReceiver(&selector); - - // Finalize construction of visualization assets - app.AssetBindAll(); - app.AssetUpdateAll(); - - // ----------------- - // Initialize output - // ----------------- - - state_output = state_output || povray_output; - - if (state_output) { - if (ChFileutils::MakeDirectory(out_dir.c_str()) < 0) { - std::cout << "Error creating directory " << out_dir << std::endl; - return 1; - } - } - -/* - utils::CSV_writer csv("\t"); - csv.stream().setf(std::ios::scientific | std::ios::showpos); - csv.stream().precision(6); -*/ - utils::ChRunningAverage fwd_acc_GC_filter(filter_window_size); - utils::ChRunningAverage lat_acc_GC_filter(filter_window_size); - - utils::ChRunningAverage fwd_acc_driver_filter(filter_window_size); - utils::ChRunningAverage lat_acc_driver_filter(filter_window_size); - - std::ofstream myfile1; - myfile1.open(data_path+"paths/position.txt",std::ofstream::out | std::ofstream::trunc); - //get mass and moment of inertia about z axis - n.setParam("vehicle/common/m",my_hmmwv.GetVehicleMass()); - const ChMatrix33<> inertia_mtx= my_hmmwv.GetChassisBody()->GetInertia(); - double Izz=inertia_mtx.GetElement(2,2); - n.setParam("vehicle/common/Izz",Izz); - // get distance to front and rear axles - // enum chrono::vehicle::VehicleSide LEFT; - // enum chrono::vehicle::VehicleSide RIGHT; - ChVector<> veh_com= my_hmmwv.GetVehicleCOMPos(); - ChVector<> la_pos=my_hmmwv.GetSuspension(0)->GetSpindlePos(chrono::vehicle::VehicleSide::RIGHT); - ChVector<> lb_pos=my_hmmwv.GetSuspension(0)->GetSpindlePos(chrono::vehicle::VehicleSide::LEFT); - double la_length, lb_length; - ChVector<> la_diff; - la_diff.Sub(veh_com,la_pos); - ChVector<> lb_diff; - lb_diff.Sub(veh_com,lb_pos); - la_length=la_diff.Length(); - lb_length=lb_diff.Length(); - n.setParam("vehicle/common/la",la_length); - n.setParam("vehicle/common/lb",lb_length); - - // get friction and restitution coefficients - // float frict_coeff, rest_coeff; - frict_coeff = my_hmmwv.GetWheel(0)->GetCoefficientFriction(); - rest_coeff = my_hmmwv.GetWheel(0)->GetCoefficientRestitution(); - n.setParam("vehicle/common/frict_coeff",frict_coeff); - n.setParam("vehicle/common/rest_coeff",rest_coeff); - - // set up the controller - double Kp, Ki, Kd, Kw; - std::string windup_method; - n.getParam("controller/Kp",Kp); - n.getParam("controller/Ki",Ki); - n.getParam("controller/Kd",Kd); - n.getParam("controller/Kw",Kw); - n.getParam("controller/anti_windup",windup_method); - n.getParam("controller/time_shift", time_shift); - - controller.set_PID(Kp, Ki, Kd, Kw); - controller.set_step_size(step_size); - controller.set_output_limit(-1.0, 1.0); - controller.set_windup_metohd(windup_method); - controller.initialize(); - ae_int_t natural_bound_type = 2; - - std::cout<< "Go into the loop..." << std::endl; - - while(n.ok()){ - while (running) { - if(gui_switch) app.GetDevice()->run(); - ros::spinOnce(); - n.setParam("system/chrono/flags/running",true); - - // ros::Subscriber sub = n.subscribe("desired_ref", 1, ¶meters::controlCallback, &hmmwv_params); - - // Render scene and output POV-Ray data - if (hmmwv_params.sim_frame % hmmwv_params.render_steps == 0 && gui_switch) { - - app.BeginScene(true, true, irr::video::SColor(255, 140, 161, 192)); - app.DrawAll(); - app.EndScene(); - - hmmwv_params.render_frame++; - } - - ros_chrono_msgs::veh_status data_out; - /* - ChVector<> acc_CG = my_hmmwv.GetVehicle().GetChassisBody()->GetPos_dtdt(); - ChVector<> acc_driver = my_hmmwv.GetVehicle().GetVehicleAcceleration(driver_pos); - double fwd_acc_CG = fwd_acc_GC_filter.Add(acc_CG.x()); - double lat_acc_CG = lat_acc_GC_filter.Add(acc_CG.y()); - double fwd_acc_driver = fwd_acc_driver_filter.Add(acc_driver.x()); - double lat_acc_driver = lat_acc_driver_filter.Add(acc_driver.y());*/ - double time = hmmwv_params.my_hmmwv.GetSystem()->GetChTime(); - - // End simulation - if (time >= t_end) - break; - - real_1d_array t_array; - real_1d_array steering_array; - real_1d_array speed_array; - - t_array.setcontent(traj_t); - steering_array.setcontent(traj_sa); - speed_array.setcontent(traj_ux); - spline1dinterpolant s_ux; - spline1dinterpolant s_sa; - spline1dbuildcubic(t_array, speed_array, s_ux); - target_speed_interp = spline1dcalc(s_ux, time + time_shift); - spline1dbuildcubic(t_array, steering_array, s_sa); - target_steering_interp = spline1dcalc(s_sa, time); - - double speed_error = target_speed_interp - speed; - controller_output = controller.control(speed_error); - - target_steering_interp = target_steering_interp / PI * 180.0 / maximum_steering_angle * 2; - - hmmwv_params.target_speed = target_speed_interp; - - // Hack for acceleration-braking maneuver - /* // on-off controller - bool braking = false; - if (my_hmmwv.GetVehicle().GetVehicleSpeed() > hmmwv_params.target_speed) - braking = true; - if (braking) { - hmmwv_params.throttle_input = 0; - hmmwv_params.braking_input = 1; - } - else { - hmmwv_params.throttle_input = 1; - hmmwv_params.braking_input = 0; - } - */ - // pid controller - if (controller_output > 0){ - hmmwv_params.throttle_input = controller_output; - hmmwv_params.braking_input = 0; - } - else{ - hmmwv_params.throttle_input = 0; - hmmwv_params.braking_input = -controller_output; - } - - // Hack for steering maneuver - hmmwv_params.steering_input = target_steering_interp; - - - // std::cout << "Chrono steering input: " << hmmwv_params.steering_input < global_pos = hmmwv_params.my_hmmwv.GetVehicleCOMPos();//global location of chassis reference frame origin - ChQuaternion<> global_orntn = hmmwv_params.my_hmmwv.GetVehicleRot();//global orientation as quaternion - ChVector<> rot_dt = hmmwv_params.my_hmmwv.GetChassisBody()->GetWvel_loc();//global orientation as quaternion - ChVector<> global_velCOM = hmmwv_params.my_hmmwv.GetChassisBody()->GetPos_dt(); - ChVector<> global_accCOM = hmmwv_params.my_hmmwv.GetChassisBody()->GetPos_dtdt(); - //ChVector<> euler_ang = global_orntn.Q_to_Rotv(); //convert to euler angles - //ChPacejkaTire<> slip_angle = GetSlipAngle() - double slip_angle = tire_front_left.GetLongitudinalSlip(); - speed = hmmwv_params.my_hmmwv.GetVehicleSpeedCOM(); - - double q0 = global_orntn[0]; - double q1 = global_orntn[1]; - double q2 = global_orntn[2]; - double q3 = global_orntn[3]; - - double yaw_val=atan2(2*(q0*q3+q1*q2),1-2*(q2*q2+q3*q3)); - double theta_val=asin(2*(q0*q2-q3*q1)); - double phi_val= atan2(2*(q0*q1+q2*q3),1-2*(q1*q1+q2*q2)); - - n.setParam("state/chrono/t",time); //time in chrono simulation - n.setParam("state/chrono/x", global_pos[0]) ; - n.setParam("state/chrono/yVal",global_pos[1]); - n.setParam("state/chrono/ux",fabs(global_velCOM[0])); //speed measured at the origin of the chassis reference frame. - n.setParam("state/chrono/v", global_velCOM[1]); - n.setParam("state/chrono/ax", global_accCOM[0]); - n.setParam("state/chrono/psi",yaw_val); //in radians - n.setParam("state/chrono/theta",theta_val); //in radians - n.setParam("state/chrono/phi",phi_val); //in radians - n.setParam("state/chrono/r",-rot_dt[2]);//yaw rate - n.setParam("state/chrono/sa",slip_angle); //slip angle - n.setParam("state/chrono/control/thr",hmmwv_params.throttle_input); //throttle input in the range [0,+1] - n.setParam("state/chrono/control/brk",hmmwv_params.braking_input); //braking input in the range [0,+1] - n.setParam("state/chrono/control/str",hmmwv_params.steering_input); //steeering input in the range [-1,+1] - - n.setParam("system/simulation_time", time); - - data_out.t_chrono=time; //time in chrono simulation - data_out.x_pos= global_pos[0]; - data_out.y_pos=global_pos[1]; - data_out.x_v= fabs(global_velCOM[0]); //speed measured at the origin of the chassis reference frame. - data_out.y_v= global_velCOM[1]; - data_out.x_a= global_accCOM[0]; - data_out.yaw_curr=yaw_val; //in radians - data_out.yaw_rate=-rot_dt[2];//yaw rate - data_out.sa=slip_angle; //slip angle - data_out.thrt_in=hmmwv_params.throttle_input; //throttle input in the range [0,+1] - data_out.brk_in=hmmwv_params.braking_input; //braking input in the range [0,+1] - data_out.str_in=hmmwv_params.steering_input; //steeering input in the range [-1,+1] - - vehicleinfo_pub.publish(data_out); - // loop_rate.sleep(); - - myfile1 << ' ' << global_pos[0] << ' '<< global_pos[1] <<' ' << global_pos[2] << '\n'; - n.getParam("system/" + planner_namespace + "/flags/goal_attained",goal_attained); - if(goal_attained){ - n.setParam("system/goal_attained","true"); - n.setParam("system/chrono/flags/running","false"); - running = false; - } - } - } -/* - if (state_output){ - csv.write_to_file(out_dir + "/state.out"); - }*/ -myfile1.close(); - - return 0; -} diff --git a/ros/src/models/chrono/ros_chrono/old/trajectory_follower_origin.cpp b/ros/src/models/chrono/ros_chrono/old/trajectory_follower_origin.cpp deleted file mode 100644 index 3e54fde5..00000000 --- a/ros/src/models/chrono/ros_chrono/old/trajectory_follower_origin.cpp +++ /dev/null @@ -1,651 +0,0 @@ -// ============================================================================= -// PROJECT CHRONO - http://projectchrono.org -// -// Copyright (c) 2014 projectchrono.org -// All rights reserved. -// -// Use of this source code is governed by a BSD-style license that can be found -// in the LICENSE file at the top level of the distribution and at -// http://projectchrono.org/license-chrono.txt. -// -// ============================================================================= -// Authors: Radu Serban -// ============================================================================= -// -// Demonstration of a steering path-follower PID controller. -// -// The vehicle reference frame has Z up, X towards the front of the vehicle, and -// Y pointing to the left. -// TO DO: -// Find proper yaw rate calculation -// Subsscribe to msg from obstacle_avoidance_chrono, callback to that to calculate ChBezierCurve -// ============================================================================= - -#include -#include -#include "boost/bind.hpp" -#include "chrono/core/ChFileutils.h" -#include "chrono/core/ChRealtimeStep.h" -#include "chrono/utils/ChFilters.h" -#include -#include -#include "ros/ros.h" -#include "std_msgs/String.h" -#include "ros_chrono_msgs/veh_status.h" -#include "nloptcontrol_planner/Trajectory.h" -#include -#include -#include -#include -//#include "tf/tf.h" -#include -#include "chrono_vehicle/ChVehicleModelData.h" -#include "chrono_vehicle/terrain/RigidTerrain.h" -#include "chrono_vehicle/driver/ChIrrGuiDriver.h" -#include "chrono_vehicle/driver/ChPathFollowerDriver.h" -#include "chrono_vehicle/wheeled_vehicle/utils/ChWheeledVehicleIrrApp.h" -#include -#include "chrono_models/vehicle/hmmwv/HMMWV.h" - -#include "chrono_thirdparty/rapidjson/document.h" -#include "chrono_thirdparty/rapidjson/filereadstream.h" - -#define PI 3.1415926535 -//using veh_status.msg -using namespace chrono; -using namespace chrono::geometry; -using namespace chrono::vehicle; -using namespace chrono::vehicle::hmmwv; - -using namespace alglib; - -using namespace rapidjson; -// ============================================================================= -// Problem parameters -// Main Data Path -//std::string data_path("/home/shreyas/.julia/v0.6/MAVs/catkin_ws/data/vehicle/"); -std::string data_path("../../../src/models/chrono/ros_chrono/src/data/vehicle/"); -//std::string data_path("src/system/chrono/ros_chrono/src/data/vehicle/"); -// Contact method type -ChMaterialSurface::ContactMethod contact_method = ChMaterialSurface::SMC; - -// Type of tire model (RIGID, LUGRE, FIALA, or PACEJKA) -TireModelType tire_model = TireModelType::RIGID; - -// Input file name for PACEJKA tires if they are selected -std::string pacejka_tire_file(data_path+"hmmwv/tire/HMMWV_pacejka.tir"); -//std::string pacejka_tire_file("hmmwv/tire/HMMWV_pacejka.tir"); -// Type of powertrain model (SHAFTS or SIMPLE) -PowertrainModelType powertrain_model = PowertrainModelType::SIMPLE; - -// Drive type (FWD, RWD, or AWD) -DrivelineType drive_type = DrivelineType::RWD; - -// Visualization type for vehicle parts (PRIMITIVES, MESH, or NONE) -VisualizationType chassis_vis_type = VisualizationType::PRIMITIVES; -VisualizationType suspension_vis_type = VisualizationType::PRIMITIVES; -VisualizationType steering_vis_type = VisualizationType::PRIMITIVES; -VisualizationType wheel_vis_type = VisualizationType::NONE; -VisualizationType tire_vis_type = VisualizationType::PRIMITIVES; - -// Input file names for the path-follower driver model -std::string steering_controller_file(data_path+"generic/driver/SteeringController.json"); -//std::string steering_controller_file("generic/driver/SteeringController.json"); -std::string speed_controller_file(data_path+"generic/driver/SpeedController.json"); -//std::string speed_controller_file("generic/driver/SpeedController.json"); -// std::string path_file("paths/straight.txt"); -std::string path_file(data_path+"paths/my_path.txt"); - -// Rigid terrain dimensions -double terrainHeight = 0; -double terrainLength = 500.0; // size in X direction -double terrainWidth = 500.0; // size in Y direction - -// Point on chassis tracked by the chase camera -ChVector<> trackPoint(0.0, 0.0, 1.75); - -// Simulation step size -double step_size = 1e-2; -double tire_step_size = step_size; - -// Simulation end time -double t_end = 1000; - -// Render FPS -double fps = 60; - -// Debug logging -bool debug_output = false; -double debug_fps = 10; - -// Output directories -const std::string out_dir = GetChronoOutputPath() + "STEERING_CONTROLLER"; -const std::string pov_dir = out_dir + "/POVRAY"; - -// POV-Ray output -bool povray_output = false; - -// Vehicle state output (forced to true if povray output enabled) -bool state_output = false; -int filter_window_size = 20; - -// In src/data/vehicle/hmmwv/steering/HMMWV_PitmanArm.json revolution joint -double speed = 0.0; -double maximum_steering_angle = 50.0; -// Controller output -double target_steering_interp = 0.0; -double target_speed_interp = 0.0; -double controller_output = 0.0; -PID controller; - -// ============================================================================= - -// Custom Irrlicht event receiver for selecting current driver model. -class ChDriverSelector : public irr::IEventReceiver { - public: - ChDriverSelector(const ChVehicle& vehicle, ChIrrGuiDriver* driver_gui) - : m_vehicle(vehicle), - m_driver_gui(driver_gui), - m_driver(m_driver_gui), - m_using_gui(true) {} - - ChDriver* GetDriver() { return m_driver; } - bool UsingGUI() const { return m_using_gui; } - - virtual bool OnEvent(const irr::SEvent& event) { - return false; - } - - private: - bool m_using_gui; - const ChVehicle& m_vehicle; - ChIrrGuiDriver* m_driver_gui; - ChDriver* m_driver; -}; - -struct parameters -{ - RigidTerrain terrain; - HMMWV_Reduced my_hmmwv; - ChRealtimeStepTimer realtime_timer; - int sim_frame; - double steering_input; - double throttle_input; - double braking_input; - std::vector x_traj_curr; - std::vector y_traj_curr; - std::vector x_traj_prev; - std::vector y_traj_prev; - double target_speed; - int render_steps; - int render_frame; -} ; - -void waitForLoaded(ros::NodeHandle &n){ - bool planner_init = false; - std::string planner_namespace; - n.getParam("system/planner",planner_namespace); - n.getParam("system/"+planner_namespace+"/flags/initialized",planner_init); - while(!planner_init){ - usleep(500); // < my question - n.getParam("system/"+planner_namespace+"/flags/initialized",planner_init); - - } - usleep(500); //sleep another 500ms to ensure everything is loaded. - //continue on here -} - -void controlCallback(const nloptcontrol_planner::Trajectory::ConstPtr& control_msg){ - double time = ros::Time::now().toSec(); - std::vector traj_t = control_msg->t; - std::vector traj_sa = control_msg->sa; - std::vector traj_ux = control_msg->ux; - std::cout << "Current time: "<< time << " "; - - std::cout << "Time trajectory: " << " "; - for(int i = 0; i < traj_t.size(); i++) - std::cout << traj_t[i] << " "; - std::cout << std::endl; - - std::cout << "Speed trajectory: " << " "; - for(int i = 0; i < traj_ux.size(); i++) - std::cout << traj_ux[i] << " "; - std::cout << std::endl; - - std::cout << "Steering trajectory: " << " "; - for(int i = 0; i < traj_sa.size(); i++) - std::cout << traj_sa[i] << " "; - std::cout << std::endl; - - real_1d_array t_array; - real_1d_array steering_array; - real_1d_array speed_array; - - t_array.setcontent(traj_t); - steering_array.setcontent(traj_sa); - speed_array.setcontent(traj_ux); - spline1dinterpolant s; - ae_int_t natural_bound_type = 2; - spline1dbuildcubic(t_array, speed_array, s); - target_speed_interp = spline1dcalc(s, time); - spline1dbuildcubic(t_array, steering_array, s); - target_steering_interp = spline1dcalc(s, time); - - double speed_error = target_speed_interp - speed; - controller_output = controller.control(speed_error); - - target_steering_interp = target_steering_interp / PI * 180.0 / maximum_steering_angle; - // steering = steering * (-1); - // std::cout << "Target_speed: " << target_speed_interp << " Actual speed: " << speed << std::endl; - std::cout << "Target_steering: " << target_steering_interp << " Actual steering: " << target_steering_interp << std::endl; - std::cout << std::endl; -} - -// ============================================================================= -int main(int argc, char* argv[]) { - - unsigned int microseconds = 10000000; - std::cout << "Sleeping for ten sec..." << std::endl; - usleep(microseconds); - - char cwd[1024]; - if (getcwd(cwd, sizeof(cwd)) != NULL) - fprintf(stdout, "Current working dir: %s\n", cwd); - else - perror("getcwd() error"); - GetLog() << "Copyright (c) 2017 projectchrono.org\nChrono version: " << CHRONO_VERSION << "\n\n"; - - // read maximum_steering_angle from json - std::string filename("PitmanArm.json"); - FILE* fp = fopen(filename.c_str(), "r"); - char readBuffer[65536]; - FileReadStream is(fp, readBuffer, sizeof(readBuffer)); - fclose(fp); - Document d; - d.ParseStream(is); - maximum_steering_angle = d["Revolute Joint"]["Maximum Angle"].GetDouble(); - - SetChronoDataPath(CHRONO_DATA_DIR); - vehicle::SetDataPath("opt/chrono/chrono/data/vehicle"); - // std::cout << GetChronoDataPath() << "\n"; check path of chrono data folder - // Initialize ROS Chrono node and set node handle to n - - ros::init(argc, argv, "Traj_follower"); - ros::NodeHandle n; - n.setParam("system/chrono/flags/initialized",true); - n.getParam("system/params/step_size",step_size); - - bool planner_init; - // bool planner_init2; - - std::string planner_namespace; - n.getParam("system/planner",planner_namespace); - n.getParam("system/"+planner_namespace+"/flags/initialized",planner_init); - std::cout << "The planner state:" << planner_init << std::endl; - ros::Subscriber sub = n.subscribe(planner_namespace+"/control", 100, controlCallback); - - //planner_init2=planner_init1; - // n.getParam("system/"+planner_namespace+"/flags/initialized",planner_init2); - - if(!planner_init){ - waitForLoaded(n); - } - //std::string planner_init; - - n.getParam("system/"+planner_namespace+"/flags/initialized",planner_init); - - // Desired vehicle speed (m/s) - double target_speed; - n.getParam("hmmwv_chrono/X0/v_des",target_speed); - - //Initial Position - double x0, y0, z0, yaw0, pitch0, roll0; - bool gui_switch; - n.getParam("case/actual/X0/x",x0); - n.getParam("case/actual/X0/yVal",y0); - n.getParam("hmmwv_chrono/X0/z",z0); - n.getParam("case/actual/X0/psi",yaw0); - n.getParam("hmmwv_chrono/X0/theta",pitch0); - n.getParam("hmmwv_chrono/X0/phi",roll0); - n.getParam("system/chrono/flags/gui",gui_switch); - - bool goal_attained = false; - bool running = true; - - ChVector<> initLoc(x0, y0, z0); -// ChQuaternion<> initRot(q[0],q[1],q[2],q[3]); - - double t0 = std::cos(yaw0 * 0.5f); - double t1 = std::sin(yaw0 * 0.5f); - double t2 = std::cos(roll0 * 0.5f); - double t3 = std::sin(roll0 * 0.5f); - double t4 = std::cos(pitch0 * 0.5f); - double t5 = std::sin(pitch0 * 0.5f); - - double q0_0 = t0 * t2 * t4 + t1 * t3 * t5; - double q0_1 = t0 * t3 * t4 - t1 * t2 * t5; - double q0_2 = t0 * t2 * t5 + t1 * t3 * t4; - double q0_3 = t1 * t2 * t4 - t0 * t3 * t5; - - ChQuaternion<> initRot(q0_0,q0_1,q0_2,q0_3); - //ChQuaternion<> initRot(cos(PI/4), 0, 0, sin(PI/4)); //initial yaw of pi/2 - - ros::Publisher vehicleinfo_pub = n.advertise("vehicleinfo", 1); - - //ros::Rate loop_rate(5); - - // ------------------------------ - // Create the vehicle and terrain - // ------------------------------ - - // Create the HMMWV vehicle, set parameters, and initialize - HMMWV_Reduced my_hmmwv; - my_hmmwv.SetContactMethod(contact_method); - my_hmmwv.SetChassisFixed(false); - my_hmmwv.SetInitPosition(ChCoordsys<>(initLoc, initRot)); - my_hmmwv.SetPowertrainType(powertrain_model); - my_hmmwv.SetDriveType(drive_type); - my_hmmwv.SetTireType(tire_model); - my_hmmwv.SetTireStepSize(tire_step_size); - my_hmmwv.SetPacejkaParamfile(pacejka_tire_file); - my_hmmwv.Initialize(); - - my_hmmwv.SetChassisVisualizationType(chassis_vis_type); - my_hmmwv.SetSuspensionVisualizationType(suspension_vis_type); - my_hmmwv.SetSteeringVisualizationType(steering_vis_type); - my_hmmwv.SetWheelVisualizationType(wheel_vis_type); - my_hmmwv.SetTireVisualizationType(tire_vis_type); - - // Create the terrain - float frict_coeff, rest_coeff; - n.getParam("vehicle/common/frict_coeff",frict_coeff); - n.getParam("vehicle/common/rest_coeff",rest_coeff); - - RigidTerrain terrain(my_hmmwv.GetSystem()); - my_hmmwv.GetVehicle().GetWheel(0)->SetContactFrictionCoefficient(frict_coeff); - my_hmmwv.GetVehicle().GetWheel(0)->SetContactRestitutionCoefficient(rest_coeff); - - //terrain.SetContactFrictionCoefficient(0.9f); - //terrain.SetContactRestitutionCoefficient(0.01f); - terrain.SetContactMaterialProperties(2e7f, 0.3f); - terrain.SetColor(ChColor(1, 1, 1)); - //terrain.SetTexture(chrono::vehicle::GetDataFile("terrain/textures/tile4.jpg"), 200, 200); - terrain.SetTexture(data_path+"terrain/textures/tile4.jpg", 200, 200); - terrain.Initialize(terrainHeight, terrainLength, terrainWidth); - // --------------------------------------- - // Create the vehicle Irrlicht application - // --------------------------------------- - - ChVehicleIrrApp app(&my_hmmwv.GetVehicle(), &my_hmmwv.GetPowertrain(), L"Steering Controller Demo", - irr::core::dimension2d(800, 640)); - - app.SetHUDLocation(500, 20); - app.SetSkyBox(); - app.AddTypicalLogo(); - app.AddTypicalLights(irr::core::vector3df(-150.f, -150.f, 200.f), irr::core::vector3df(-150.f, 150.f, 200.f), 100, - 100); - app.AddTypicalLights(irr::core::vector3df(150.f, -150.f, 200.f), irr::core::vector3df(150.0f, 150.f, 200.f), 100, - 100); - app.EnableGrid(false); - app.SetChaseCamera(trackPoint, 6.0, 0.5); - - app.SetTimestep(step_size); - app.SetTryRealtime(true); - - // ------------------------- - // Create the driver systems - // ------------------------- - - // Create both a GUI driver and a path-follower and allow switching between them - ChIrrGuiDriver driver_gui(app); - driver_gui.Initialize(); - - // --------------- - // Simulation loop - // --------------- - - // Driver location in vehicle local frame - ChVector<> driver_pos = my_hmmwv.GetChassis()->GetLocalDriverCoordsys().pos; - // Number of simulation steps between miscellaneous events - double render_step_size = 1 / fps; - int render_steps = (int)std::ceil(render_step_size / step_size); - double debug_step_size = 1 / debug_fps; - int debug_steps = (int)std::ceil(debug_step_size / step_size); - - // Initialize simulation frame counter and simulation time - ChRealtimeStepTimer realtime_timer; - int sim_frame = 0; - int render_frame = 0; - - double throttle_input, steering_input, braking_input; - std::vector x_traj_curr, y_traj_curr,x_traj_prev,y_traj_prev; //Initialize xy trajectory vectors - parameters hmmwv_params{terrain,my_hmmwv,realtime_timer,sim_frame,steering_input,throttle_input,braking_input,x_traj_curr,y_traj_curr,x_traj_prev,y_traj_prev,target_speed,render_steps,render_frame}; - //Load xy parameters for the first timestep - // std::string planner_namespace; - // n.getParam("system/planner",planner_namespace); - - // ---------------------- - // Create the Bezier path - // ---------------------- - - // Create and register a custom Irrlicht event receiver to allow selecting the - // current driver model. - ChDriverSelector selector(my_hmmwv.GetVehicle(), &driver_gui); - app.SetUserEventReceiver(&selector); - - // Finalize construction of visualization assets - app.AssetBindAll(); - app.AssetUpdateAll(); - - // ----------------- - // Initialize output - // ----------------- - - state_output = state_output || povray_output; - - if (state_output) { - if (ChFileutils::MakeDirectory(out_dir.c_str()) < 0) { - std::cout << "Error creating directory " << out_dir << std::endl; - return 1; - } - } - -/* - utils::CSV_writer csv("\t"); - csv.stream().setf(std::ios::scientific | std::ios::showpos); - csv.stream().precision(6); -*/ - utils::ChRunningAverage fwd_acc_GC_filter(filter_window_size); - utils::ChRunningAverage lat_acc_GC_filter(filter_window_size); - - utils::ChRunningAverage fwd_acc_driver_filter(filter_window_size); - utils::ChRunningAverage lat_acc_driver_filter(filter_window_size); - - std::ofstream myfile1; - myfile1.open(data_path+"paths/position.txt",std::ofstream::out | std::ofstream::trunc); - //get mass and moment of inertia about z axis - n.setParam("vehicle/common/m",my_hmmwv.GetVehicle().GetVehicleMass()); - const ChMatrix33<> inertia_mtx= my_hmmwv.GetChassisBody()->GetInertia(); - double Izz=inertia_mtx.GetElement(2,2); - n.setParam("vehicle/common/Izz",Izz); - // get distance to front and rear axles - // enum chrono::vehicle::VehicleSide LEFT; - // enum chrono::vehicle::VehicleSide RIGHT; - ChVector<> veh_com= my_hmmwv.GetVehicle().GetVehicleCOMPos(); - ChVector<> la_pos=my_hmmwv.GetVehicle().GetSuspension(0)->GetSpindlePos(chrono::vehicle::VehicleSide::RIGHT); - ChVector<> lb_pos=my_hmmwv.GetVehicle().GetSuspension(0)->GetSpindlePos(chrono::vehicle::VehicleSide::LEFT); - double la_length, lb_length; - ChVector<> la_diff; - la_diff.Sub(veh_com,la_pos); - ChVector<> lb_diff; - lb_diff.Sub(veh_com,lb_pos); - la_length=la_diff.Length(); - lb_length=lb_diff.Length(); - n.setParam("vehicle/common/la",la_length); - n.setParam("vehicle/common/lb",lb_length); - - // get friction and restitution coefficients - // float frict_coeff, rest_coeff; - frict_coeff = my_hmmwv.GetVehicle().GetWheel(0)->GetCoefficientFriction(); - rest_coeff = my_hmmwv.GetVehicle().GetWheel(0)->GetCoefficientRestitution(); - n.setParam("vehicle/common/frict_coeff",frict_coeff); - n.setParam("vehicle/common/rest_coeff",rest_coeff); - - // set up the controller - controller.set_PID(0.3, 0.04, 0.001); - controller.set_step_size(step_size); - controller.set_output_limit(-1.0, 1.0); - controller.initialize(); - - std::cout<< "Go into the loop..." << std::endl; - - while(n.ok()){ - while (running) { - if(gui_switch) app.GetDevice()->run(); - hmmwv_params.target_speed = target_speed_interp; - - // Hack for acceleration-braking maneuver - /* // on-off controller - bool braking = false; - if (my_hmmwv.GetVehicle().GetVehicleSpeed() > hmmwv_params.target_speed) - braking = true; - if (braking) { - hmmwv_params.throttle_input = 0; - hmmwv_params.braking_input = 1; - } - else { - hmmwv_params.throttle_input = 1; - hmmwv_params.braking_input = 0; - } - */ - // pid controller - if (controller_output > 0){ - hmmwv_params.throttle_input = controller_output; - hmmwv_params.braking_input = 0; - } - else{ - hmmwv_params.throttle_input = 0; - hmmwv_params.braking_input = -controller_output; - } - - // Hack for steering maneuver - hmmwv_params.steering_input = target_steering_interp; - - // ros::Subscriber sub = n.subscribe("desired_ref", 1, ¶meters::controlCallback, &hmmwv_params); - - // Render scene and output POV-Ray data - if (hmmwv_params.sim_frame % hmmwv_params.render_steps == 0 && gui_switch) { - - app.BeginScene(true, true, irr::video::SColor(255, 140, 161, 192)); - app.DrawAll(); - app.EndScene(); - - - hmmwv_params.render_frame++; - } - - ros_chrono_msgs::veh_status data_out; - /* - ChVector<> acc_CG = my_hmmwv.GetVehicle().GetChassisBody()->GetPos_dtdt(); - ChVector<> acc_driver = my_hmmwv.GetVehicle().GetVehicleAcceleration(driver_pos); - double fwd_acc_CG = fwd_acc_GC_filter.Add(acc_CG.x()); - double lat_acc_CG = lat_acc_GC_filter.Add(acc_CG.y()); - double fwd_acc_driver = fwd_acc_driver_filter.Add(acc_driver.x()); - double lat_acc_driver = lat_acc_driver_filter.Add(acc_driver.y());*/ - double time = hmmwv_params.my_hmmwv.GetSystem()->GetChTime(); - - // End simulation - if (time >= t_end) - break; - - // hmmwv_params.throttle_input = selector_p->GetDriver()->GetThrottle(); - // hmmwv_params.steering_input = selector_p->GetDriver()->GetSteering(); - // hmmwv_params.braking_input = selector_p->GetDriver()->GetBraking(); - // Update modules (process inputs from other modules) - - // std::cout << "Chrono steering input: " << hmmwv_params.steering_input < global_pos = hmmwv_params.my_hmmwv.GetVehicle().GetVehicleCOMPos();//global location of chassis reference frame origin - ChQuaternion<> global_orntn = hmmwv_params.my_hmmwv.GetVehicle().GetVehicleRot();//global orientation as quaternion - ChVector<> rot_dt = hmmwv_params.my_hmmwv.GetVehicle().GetChassisBody()->GetWvel_loc();//global orientation as quaternion - ChVector<> global_velCOM = hmmwv_params.my_hmmwv.GetVehicle().GetChassisBody()->GetPos_dt(); - ChVector<> global_accCOM = hmmwv_params.my_hmmwv.GetVehicle().GetChassisBody()->GetPos_dtdt(); - //ChVector<> euler_ang = global_orntn.Q_to_Rotv(); //convert to euler angles - //ChPacejkaTire<> slip_angle = GetSlipAngle() - double slip_angle = hmmwv_params.my_hmmwv.GetTire(0)->GetLongitudinalSlip(); - speed = hmmwv_params.my_hmmwv.GetVehicle().GetVehicleSpeedCOM(); - - double q0 = global_orntn[0]; - double q1 = global_orntn[1]; - double q2 = global_orntn[2]; - double q3 = global_orntn[3]; - - double yaw_val=atan2(2*(q0*q3+q1*q2),1-2*(q2*q2+q3*q3)); - double theta_val=asin(2*(q0*q2-q3*q1)); - double phi_val= atan2(2*(q0*q1+q2*q3),1-2*(q1*q1+q2*q2)); - - n.setParam("state/chrono/state/t",time); //time in chrono simulation - n.setParam("state/chrono/state/x", global_pos[0]) ; - n.setParam("state/chrono/state/yVal",global_pos[1]); - n.setParam("state/chrono/state/ux",fabs(global_velCOM[0])); //speed measured at the origin of the chassis reference frame. - n.setParam("state/chrono/state/v", global_velCOM[1]); - n.setParam("state/chrono/state/ax", global_accCOM[0]); - n.setParam("state/chrono/state/psi",yaw_val); //in radians - n.setParam("state/chrono/state/theta",theta_val); //in radians - n.setParam("state/chrono/state/phi",phi_val); //in radians - n.setParam("state/chrono/state/r",-rot_dt[2]);//yaw rate - n.setParam("state/chrono/state/sa",slip_angle); //slip angle - n.setParam("state/chrono/control/thr",hmmwv_params.throttle_input); //throttle input in the range [0,+1] - n.setParam("state/chrono/control/brk",hmmwv_params.braking_input); //braking input in the range [0,+1] - n.setParam("state/chrono/control/str",hmmwv_params.steering_input); //steeering input in the range [-1,+1] - - data_out.t_chrono=time; //time in chrono simulation - data_out.x_pos= global_pos[0]; - data_out.y_pos=global_pos[1]; - data_out.x_v= fabs(global_velCOM[0]); //speed measured at the origin of the chassis reference frame. - data_out.y_v= global_velCOM[1]; - data_out.x_a= global_accCOM[0]; - data_out.yaw_curr=yaw_val; //in radians - data_out.yaw_rate=-rot_dt[2];//yaw rate - data_out.sa=slip_angle; //slip angle - data_out.thrt_in=hmmwv_params.throttle_input; //throttle input in the range [0,+1] - data_out.brk_in=hmmwv_params.braking_input; //braking input in the range [0,+1] - data_out.str_in=hmmwv_params.steering_input; //steeering input in the range [-1,+1] - - vehicleinfo_pub.publish(data_out); - // loop_rate.sleep(); - - myfile1 << ' ' << global_pos[0] << ' '<< global_pos[1] <<' ' << global_pos[2] << '\n'; - ros::spinOnce(); - n.getParam("system/" + planner_namespace + "/flags/goal_attained",goal_attained); - if(goal_attained){ - n.setParam("system/goal_attained","true"); - n.setParam("system/chrono/flags/running","false"); - running = false; - } - } - } -/* - if (state_output){ - csv.write_to_file(out_dir + "/state.out"); - }*/ -myfile1.close(); - - return 0; -} diff --git a/ros/src/models/chrono/ros_chrono/old/velocity_controller.cpp b/ros/src/models/chrono/ros_chrono/old/velocity_controller.cpp deleted file mode 100755 index 2722148a..00000000 --- a/ros/src/models/chrono/ros_chrono/old/velocity_controller.cpp +++ /dev/null @@ -1,410 +0,0 @@ -// ============================================================================= -// PROJECT CHRONO - http://projectchrono.org -// -// Copyright (c) 2014 projectchrono.org -// All rights reserved. -// -// Use of this source code is governed by a BSD-style license that can be found -// in the LICENSE file at the top level of the distribution and at -// http://projectchrono.org/license-chrono.txt. -// -// ============================================================================= -// Authors: Radu Serban -// ============================================================================= -// -// Demonstration of a steering path-follower PID controller. -// -// The vehicle reference frame has Z up, X towards the front of the vehicle, and -// Y pointing to the left. -// -// ============================================================================= - -// C/C++ library -#include -#include -#include -#include -#include - -// Computing tool library -#include "interpolation.h" -#include "PID.h" - -// ROS include library -#include "ros/ros.h" -#include "std_msgs/Float64.h" -#include "nloptcontrol_planner/Trajectory.h" -#include "ros_chrono_msgs/veh_status.h" - -// Chrono include library -#include "chrono/core/ChFileutils.h" -#include "chrono/core/ChRealtimeStep.h" -#include "chrono/utils/ChFilters.h" - -#include "chrono_vehicle/ChVehicleModelData.h" -#include "chrono_vehicle/terrain/RigidTerrain.h" -#include "chrono_vehicle/driver/ChIrrGuiDriver.h" -#include "chrono_vehicle/driver/ChPathFollowerDriver.h" -#include "chrono_vehicle/utils/ChVehiclePath.h" -#include "chrono_vehicle/wheeled_vehicle/utils/ChWheeledVehicleIrrApp.h" -#include "chrono_models/vehicle/hmmwv/HMMWV.h" - -using namespace chrono; -using namespace chrono::geometry; -using namespace chrono::vehicle; -using namespace chrono::vehicle::hmmwv; -using namespace alglib; - -// Default Chrono vehicle model parameters data path -std::string data_path("/opt/chrono/chrono_build/data/vehicle/"); - -// Rigid terrain dimensions -double terrainHeight = 0; -double terrainLength = 500.0; // size in X direction -double terrainWidth = 500.0; // size in Y direction - -// ROS Control Input (Topic) -std::vector traj_t(2,0); -std::vector traj_x(2,0); -std::vector traj_y(2,0); -std::vector traj_psi(2,0); -std::vector traj_sa(2,0); -std::vector traj_ux(2,0); - -// Interpolator -double traj_sa_interp = 0.0; -double traj_ux_interp = 0.0; - -// ------ -// Chrono -// ------ -// Contact method type -ChMaterialSurface::ContactMethod contact_method = ChMaterialSurface::SMC; - -// Type of tire model (RIGID, LUGRE, FIALA, PACEJKA, or TMEASY) -TireModelType tire_model = TireModelType::RIGID; - -// Type of powertrain model (SHAFTS or SIMPLE) -PowertrainModelType powertrain_model = PowertrainModelType::SHAFTS; - -// Drive type (FWD, RWD, or AWD) -DrivelineType drive_type = DrivelineType::RWD; - -// Steering type (PITMAN_ARM or PITMAN_ARM_SHAFTS) -// Note: Compliant steering requires higher PID gains. -SteeringType steering_type = SteeringType::PITMAN_ARM; - -// Visualization type for vehicle parts (PRIMITIVES, MESH, or NONE) -VisualizationType chassis_vis_type = VisualizationType::PRIMITIVES; -VisualizationType suspension_vis_type = VisualizationType::PRIMITIVES; -VisualizationType steering_vis_type = VisualizationType::PRIMITIVES; -VisualizationType wheel_vis_type = VisualizationType::PRIMITIVES; -VisualizationType tire_vis_type = VisualizationType::NONE; - -// Point on chassis tracked by the chase camera -ChVector<> trackPoint(0.0, 0.0, 1.75); - -// ============================================================================= - -void plannerCallback(const nloptcontrol_planner::Trajectory::ConstPtr& control_msgs) { - traj_t = control_msgs->t; - traj_x = control_msgs->x; - traj_y = control_msgs->y; - traj_psi = control_msgs->psi; - traj_sa = control_msgs->sa; - traj_ux = control_msgs->ux; -} - -// ============================================================================= - -int main(int argc, char* argv[]) { - - // ------------------------------ - // Initialize ROS node handle - // ------------------------------ - ros::init(argc, argv, "velocity_controller"); - ros::NodeHandle node; - - // Declare ROS subscriber to subscribe planner topic - std::string planner_namespace; - node.getParam("system/planner", planner_namespace); - ros::Subscriber planner_sub = node.subscribe(planner_namespace+"/control", 100, plannerCallback); - - // Declare ROS publisher to advertise vehicleinfo topic - std::string chrono_namespace; - node.getParam("system/chrono/namespace", chrono_namespace); - ros::Publisher vehicleinfo_pub = node.advertise(chrono_namespace+"/vehicleinfo", 1); - ros_chrono_msgs::veh_status vehicleinfo_data; - - // Load system parameters - double goal_tol = 0.1; // Path following tolerance - double target_speed = 0.0; // Desired velocity - double x0 = 0.0, y0 = 0.0, z0 = 0.5; // Initial global position - double roll0 = 0.0, pitch0 = 0.0, yaw0 = 0.0; // Initial global orientation - double x = 0, y = 0; - double goal_x = 0, goal_y = 0; // Goal position - double step_size = 5e-3; // Simulation step size - double tire_step_size = step_size / 2.0; - - node.getParam("system/params/step_size", step_size); // ROS loop rate and Chrono step size - node.getParam("system/params/goal_tol",goal_tol); - - node.getParam("state/chrono/X0/v_des", target_speed); // desired velocity - node.getParam("state/chrono/X0/theta", pitch0); // initial pitch - node.getParam("state/chrono/X0/phi", roll0); // initial roll - node.getParam("state/chrono/X0/z", z0); // initial z - node.getParam("state/chrono/x", x); // global x position - node.getParam("state/chrono/yVal", y); // global y position - - node.getParam("case/actual/X0/psi",yaw0); // initial yaw - node.getParam("case/actual/X0/x",x0); // initial x - node.getParam("case/actual/X0/yVal",y0); // initial y - - node.getParam("case/goal/x",goal_x); - node.getParam("case/goal/yVal",goal_y); - - // Load chrono vehicle_params - double frict_coeff, rest_coeff, gear_ratios; - std::vector centroidLoc, centroidOrientation; - double chassisMass; - std::vector chassisInertia; - std::vector driverLoc, driverOrientation; - std::vector motorBlockDirection, axleDirection; - double driveshaftInertia, differentialBoxInertia, conicalGearRatio, differentialRatio; - std::vector gearRatios; - double steeringLinkMass, steeringLinkRadius, steeringLinkLength; - std::vector steeringLinkInertia; - double pinionRadius, pinionMaxAngle, maxBrakeTorque; - node.getParam("vehicle/chrono/vehicle_params/frict_coeff", frict_coeff); - node.getParam("vehicle/chrono/vehicle_params/rest_coeff", rest_coeff); - node.getParam("vehicle/chrono/vehicle_params/gearRatios", gear_ratios); - node.getParam("vehicle/chrono/vehicle_params/centroidLoc", centroidLoc); - node.getParam("vehicle/chrono/vehicle_params/centroidOrientation", centroidOrientation); - node.getParam("vehicle/chrono/vehicle_params/chassisMass", chassisMass); - node.getParam("vehicle/chrono/vehicle_params/chassisInertia", chassisInertia); - node.getParam("vehicle/chrono/vehicle_params/driverLoc", driverLoc); - node.getParam("vehicle/chrono/vehicle_params/driverOrientation", driverOrientation); - node.getParam("vehicle/chrono/vehicle_params/motorBlockDirection", motorBlockDirection); - node.getParam("vehicle/chrono/vehicle_params/axleDirection", axleDirection); - node.getParam("vehicle/chrono/vehicle_params/driveshaftInertia", driveshaftInertia); - node.getParam("vehicle/chrono/vehicle_params/differentialBoxInertia", differentialBoxInertia); - node.getParam("vehicle/chrono/vehicle_params/conicalGearRatio", conicalGearRatio); - node.getParam("vehicle/chrono/vehicle_params/differentialRatio", differentialRatio); - node.getParam("vehicle/chrono/vehicle_params/gearRatios", gearRatios); - node.getParam("vehicle/chrono/vehicle_params/steeringLinkMass", steeringLinkMass); - node.getParam("vehicle/chrono/vehicle_params/steeringLinkInertia", steeringLinkInertia); - node.getParam("vehicle/chrono/vehicle_params/steeringLinkRadius", steeringLinkRadius); - node.getParam("vehicle/chrono/vehicle_params/steeringLinkLength", steeringLinkLength); - node.getParam("vehicle/chrono/vehicle_params/pinionRadius", pinionRadius); - node.getParam("vehicle/chrono/vehicle_params/pinionMaxAngle", pinionMaxAngle); - node.getParam("vehicle/chrono/vehicle_params/maxBrakeTorque", maxBrakeTorque); - - // Load PID controller parameters and set up PID controller - double Kp = 0.5, Ki = 0.0, Kd = 0.0, Kw = 0.0, time_shift = 3.0; // PID controller parameter - std::string windup_method("clamping"); // Anti-windup method - double controller_output = 0.0; - PID controller; - node.getParam("controller/Kp",Kp); - node.getParam("controller/Ki",Ki); - node.getParam("controller/Kd",Kd); - node.getParam("controller/Kw",Kw); - node.getParam("controller/anti_windup", windup_method); - node.getParam("controller/time_shift", time_shift); - - controller.set_PID(Kp, Ki, Kd, Kw); - controller.set_step_size(step_size); - controller.set_output_limit(-1.0, 1.0); - controller.set_windup_metohd(windup_method); - controller.initialize(); - - // Declare loop rate - ros::Rate loop_rate(int(1.0/step_size)); - - // Set initial vehicle location and orientation - ChVector<> initLoc(x0, y0, z0); - - // convert yaw pitch roll to quaternion - double t0 = std::cos(yaw0 * 0.5f); - double t1 = std::sin(yaw0 * 0.5f); - double t2 = std::cos(roll0 * 0.5f); - double t3 = std::sin(roll0 * 0.5f); - double t4 = std::cos(pitch0 * 0.5f); - double t5 = std::sin(pitch0 * 0.5f); - - double q0_0 = t0 * t2 * t4 + t1 * t3 * t5; - double q0_1 = t0 * t3 * t4 - t1 * t2 * t5; - double q0_2 = t0 * t2 * t5 + t1 * t3 * t4; - double q0_3 = t1 * t2 * t4 - t0 * t3 * t5; - - ChQuaternion<> initRot(q0_0,q0_1,q0_2,q0_3); - - // ------------------------------ - // Create the vehicle and terrain - // ------------------------------ - - // Create the HMMWV vehicle, set parameters, and initialize - HMMWV_Full my_hmmwv; - my_hmmwv.SetContactMethod(contact_method); - my_hmmwv.SetChassisFixed(false); - my_hmmwv.SetInitPosition(ChCoordsys<>(initLoc, initRot)); - my_hmmwv.SetPowertrainType(powertrain_model); - my_hmmwv.SetDriveType(drive_type); - my_hmmwv.SetSteeringType(steering_type); - my_hmmwv.SetTireType(tire_model); - my_hmmwv.SetTireStepSize(tire_step_size); - my_hmmwv.SetVehicleStepSize(step_size); - my_hmmwv.Initialize(); - - my_hmmwv.SetChassisVisualizationType(chassis_vis_type); - my_hmmwv.SetSuspensionVisualizationType(suspension_vis_type); - my_hmmwv.SetSteeringVisualizationType(steering_vis_type); - my_hmmwv.SetWheelVisualizationType(wheel_vis_type); - my_hmmwv.SetTireVisualizationType(tire_vis_type); - - double maximum_steering_angle = my_hmmwv.GetVehicle().GetMaxSteeringAngle(); - - // Create the terrain - RigidTerrain terrain(my_hmmwv.GetSystem()); - auto patch = terrain.AddPatch(ChCoordsys<>(ChVector<>(0, 0, terrainHeight - 5), QUNIT), - ChVector<>(terrainLength, terrainWidth, 10)); - patch->SetContactFrictionCoefficient(frict_coeff); - patch->SetContactRestitutionCoefficient(rest_coeff); - patch->SetContactMaterialProperties(2e7f, 0.3f); - patch->SetColor(ChColor(1, 1, 1)); - patch->SetTexture(data_path+"terrain/textures/tile4.jpg", 200, 200); - terrain.Initialize(); - - // --------------------------------------- - // Create the vehicle Irrlicht application - // --------------------------------------- - - ChVehicleIrrApp app(&my_hmmwv.GetVehicle(), &my_hmmwv.GetPowertrain(), L"velocity_controller demo", - irr::core::dimension2d(800, 640)); - - app.SetHUDLocation(500, 20); - app.AddTypicalLights(irr::core::vector3df(-150.f, -150.f, 200.f), irr::core::vector3df(-150.f, 150.f, 200.f), 100, - 100); - app.AddTypicalLights(irr::core::vector3df(150.f, -150.f, 200.f), irr::core::vector3df(150.0f, 150.f, 200.f), 100, - 100); - app.EnableGrid(false); - app.SetChaseCamera(trackPoint, 6.0, 0.5); - - app.SetTimestep(step_size); - - // Finalize construction of visualization assets - app.AssetBindAll(); - app.AssetUpdateAll(); - - // --------------- - // Simulation loop - // --------------- - - // Driver location in vehicle local frame - ChVector<> driver_pos = my_hmmwv.GetChassis()->GetLocalDriverCoordsys().pos; - - // Initialize simulation frame counter and simulation time - ChRealtimeStepTimer realtime_timer; - - // Vehicle velocity - double speed = 0.0; - // Collect controller output data from modules (for inter-module communication) - double throttle_input = 0; - double steering_input = 0; - double braking_input = 0; - - while (ros::ok()) { - - // Extract system state - double time = my_hmmwv.GetSystem()->GetChTime(); - - // -------------------------- - // interpolation using ALGLIB - // -------------------------- - // real_1d_array t_array; - // real_1d_array sa_array; - // real_1d_array ux_array; - - // t_array.setcontent(traj_t); - // sa_array.setcontent(traj_sa); - // ux_array.setcontent(traj_ux); - // spline1dinterpolant s_ux; - // spline1dinterpolant s_sa; - // spline1dbuildcubic(t_array, ux_array, s_ux); - // traj_ux_interp = spline1dcalc(s_ux, time + time_shift); - // spline1dbuildcubic(t_array, sa_array, s_sa); - // traj_sa_interp = spline1dcalc(s_sa, time); - - // PID controller output for throttle or brake - // double ux_err = traj_ux_interp - speed; - double ux_err = traj_ux[0] - speed; - controller_output = controller.control(ux_err); - if (controller_output > 0){ - throttle_input = controller_output; - braking_input = 0; - } - else { - throttle_input = 0; - braking_input = -controller_output; - } - - // Steering angle output - // traj_sa_interp = traj_sa_interp; - steering_input = traj_sa[0] / M_PI * 180.0 / maximum_steering_angle; - - app.BeginScene(true, true, irr::video::SColor(255, 140, 161, 192)); - app.DrawAll(); - - // Update modules (process inputs from other modules) - terrain.Synchronize(time); - my_hmmwv.Synchronize(time, steering_input, braking_input, throttle_input, terrain); - app.Synchronize("", steering_input, throttle_input, braking_input); - - // Advance simulation for one timestep for all modules - double step = realtime_timer.SuggestSimulationStep(step_size); - terrain.Advance(step); - my_hmmwv.Advance(step); - app.Advance(step); - - // Get vehicle information from Chrono vehicle model - ChVector<> pos_global = my_hmmwv.GetVehicle().GetVehicleCOMPos(); - ChVector<> spd_global = my_hmmwv.GetChassisBody()->GetPos_dt(); - ChVector<> acc_global = my_hmmwv.GetChassisBody()->GetPos_dtdt(); - ChQuaternion<> rot_global = my_hmmwv.GetVehicle().GetVehicleRot(); // global orientation as quaternion - ChVector<> rot_dt = my_hmmwv.GetChassisBody()->GetWvel_loc(); //global orientation as quaternion - - double slip_angle = my_hmmwv.GetTire(0)->GetSlipAngle(); - speed = my_hmmwv.GetVehicle().GetVehicleSpeedCOM(); - - double q0 = rot_global[0]; - double q1 = rot_global[1]; - double q2 = rot_global[2]; - double q3 = rot_global[3]; - - double yaw_val=atan2(2*(q0*q3+q1*q2),1-2*(q2*q2+q3*q3)); - double theta_val=asin(2*(q0*q2-q3*q1)); - double phi_val= atan2(2*(q0*q1+q2*q3),1-2*(q1*q1+q2*q2)); - - // Update vehicleinfo_data - vehicleinfo_data.t_chrono = time; // time in chrono simulation - vehicleinfo_data.x_pos = pos_global[0]; - vehicleinfo_data.y_pos = pos_global[1]; - vehicleinfo_data.x_v = spd_global[0]; // speed measured at the origin of the chassis reference frame. - vehicleinfo_data.y_v = spd_global[1]; - vehicleinfo_data.x_a = acc_global[0]; - vehicleinfo_data.yaw_curr = yaw_val; // in radians - vehicleinfo_data.yaw_rate = -rot_dt[2];// yaw rate - vehicleinfo_data.sa = slip_angle; // slip angle - vehicleinfo_data.thrt_in = throttle_input; // throttle input in the range [0,+1] - vehicleinfo_data.brk_in = braking_input; // braking input in the range [0,+1] - vehicleinfo_data.str_in = steering_input; // steeering input in the range [-1,+1] - - // Publish current vehicle information - vehicleinfo_pub.publish(vehicleinfo_data); - - app.EndScene(); - ros::spinOnce(); - loop_rate.sleep(); - } - - return 0; -} diff --git a/ros/src/models/chrono/ros_chrono/package.xml b/ros/src/models/chrono/ros_chrono/package.xml index e30ceb7c..6685cf27 100644 --- a/ros/src/models/chrono/ros_chrono/package.xml +++ b/ros/src/models/chrono/ros_chrono/package.xml @@ -58,7 +58,6 @@ rospy std_msgs message_generation - ros_chrono_msgs mavs_msgs nloptcontrol_planner interpolation @@ -68,14 +67,12 @@ roscpp rospy std_msgs - ros_chrono_msgs mavs_msgs Chrono roscpp rospy std_msgs message_runtime - ros_chrono_msgs mavs_msgs Chrono interpolation diff --git a/ros/src/models/chrono/ros_chrono/src/path_follower.cpp b/ros/src/models/chrono/ros_chrono/src/path_follower.cpp index d2446868..977b2934 100644 --- a/ros/src/models/chrono/ros_chrono/src/path_follower.cpp +++ b/ros/src/models/chrono/ros_chrono/src/path_follower.cpp @@ -41,6 +41,7 @@ #include "chrono/utils/ChFilters.h" #include "chrono_vehicle/ChVehicleModelData.h" #include "chrono_vehicle/terrain/RigidTerrain.h" +#include "chrono_vehicle/terrain/FlatTerrain.h" #include "chrono_vehicle/driver/ChIrrGuiDriver.h" #include "chrono_vehicle/driver/ChPathFollowerDriver.h" #include "chrono_vehicle/utils/ChVehiclePath.h" @@ -68,6 +69,7 @@ double traj_sa_interp = 0.0; double traj_ux_interp = 0.0; double traj_x_interp = 0.0; double traj_y_interp = 0.0; +int current_index = 0; // ------ // Chrono @@ -96,526 +98,545 @@ VisualizationType wheel_vis_type = VisualizationType::PRIMITIVES; VisualizationType tire_vis_type = VisualizationType::NONE; // ============================================================================= -void waitForLoaded(ros::NodeHandle &node){ - bool is_init; - node.setParam("system/chrono/flags/initialized", true); - node.getParam("system/flags/initialized", is_init); - - while (!is_init) { - node.getParam("system/flags/initialized", is_init); - } +void waitForLoaded(ros::NodeHandle &node) { + bool is_init; + node.setParam("system/chrono/flags/initialized", true); + node.getParam("system/flags/initialized", is_init); + + while (!is_init) { + node.getParam("system/flags/initialized", is_init); + } } ChVector<> global2veh(double yaw_angle, ChVector<> ChVector_global) { - // Construct rotation matrix - ChVector<> R1(std::cos(yaw_angle), std::sin(yaw_angle), 0.0); - ChVector<> R2(-std::sin(yaw_angle), std::cos(yaw_angle), 0.0); - ChVector<> R3(0.0, 0.0, 1.0); + // Construct rotation matrix + ChVector<> R1(std::cos(yaw_angle), std::sin(yaw_angle), 0.0); + ChVector<> R2(-std::sin(yaw_angle), std::cos(yaw_angle), 0.0); + ChVector<> R3(0.0, 0.0, 1.0); - auto veh_x = R1 ^ ChVector_global; // dot product in chrono - auto veh_y = R2 ^ ChVector_global; // dot product in chrono - auto veh_z = R3 ^ ChVector_global; // dot product in chrono + auto veh_x = R1 ^ ChVector_global; // dot product in chrono + auto veh_y = R2 ^ ChVector_global; // dot product in chrono + auto veh_z = R3 ^ ChVector_global; // dot product in chrono - return ChVector<> (veh_x, veh_y, veh_z); + return ChVector<>(veh_x, veh_y, veh_z); } -bool receive_flag = false; - void plannerCallback(const nloptcontrol_planner::Trajectory::ConstPtr& control_msgs) { - traj_t = control_msgs->t; - traj_x = control_msgs->x; - traj_y = control_msgs->y; - traj_psi = control_msgs->psi; - traj_sa = control_msgs->sa; - traj_ux = control_msgs->ux; - receive_flag = true; - - if (traj_ux.empty() || traj_x.empty() || traj_x.size() <= 1) { - ROS_INFO("Error: Trajectory only has one point or less!"); - } - + traj_t = control_msgs->t; + traj_x = control_msgs->x; + traj_y = control_msgs->y; + traj_psi = control_msgs->psi; + traj_sa = control_msgs->sa; + traj_ux = control_msgs->ux; + + if (traj_ux.empty() || traj_x.empty() || traj_x.size() <= 1) { + ROS_INFO("Error: Trajectory only has one point or less!"); + } + } int get_nearest_index(const ChVector<>& pos_global, - const std::vector& traj_x, - const std::vector& traj_y) { - - if (traj_x.empty() || traj_x.size() == 1) { - return 0; - } - - int index = 0; - double min_dist_sqr = pow(pos_global[0] - traj_x[0], 2) + pow(pos_global[1] - traj_x[0], 2); - - for (int i = 1; i < traj_x.size() - 1; i++) { - double dist_sqr = pow(pos_global[0] - traj_x[i], 2) + pow(pos_global[1] - traj_x[i], 2); - if (dist_sqr < min_dist_sqr) { - min_dist_sqr = dist_sqr; - index = i; - } - } - return index; + const std::vector& traj_x, + const std::vector& traj_y) { + + if (traj_x.empty() || traj_x.size() == 1) { + return 0; + } + + int index = 0; + double min_dist_sqr = pow(pos_global[0] - traj_x[0], 2) + pow(pos_global[1] - traj_y[0], 2); + + for (int i = 1; i < traj_x.size() - 1; i++) { + double dist_sqr = pow(pos_global[0] - traj_x[i], 2) + pow(pos_global[1] - traj_y[i], 2); + if (dist_sqr < min_dist_sqr) { + min_dist_sqr = dist_sqr; + index = i; + } + } + return index; } -double get_PosError(const ChVector<>& pos_global, - const std::vector& traj_x, - const std::vector& traj_y, - int index) { - - if (traj_x.empty() || traj_x.size() == 1) { - return 0; - } - - double traj_dir_x = traj_x[index + 1] - traj_x[index]; - double traj_dir_y = traj_y[index + 1] - traj_y[index]; - double traj_len = std::sqrt(traj_dir_x * traj_dir_x + traj_dir_y * traj_dir_y); - if (traj_len < 0.01) return 0; - traj_dir_x /= traj_len; - traj_dir_y /= traj_len; - - double car2traj_x = traj_x[index] - pos_global[0]; - double car2traj_y = traj_y[index] - pos_global[1]; - double PosError = car2traj_y * traj_dir_x - car2traj_x * traj_dir_y; - - return PosError; +unsigned int getTargetPos(const ChVector<>& pos_global, const std::vector& traj_x, const std::vector& traj_y, const std::vector& traj_ux, + double& target_speed, double cur_speed, double& x_target, double& y_target) { + unsigned int index_closest = get_nearest_index(pos_global, traj_x, traj_y); + double dist_target = std::min(40.0, std::max(30.0, 1.5*cur_speed)); //double dist_target = std::min(40.0, std::max(30.0, 1.5*cur_speed)); + double index_target = index_closest; + double dist_last; + double dist_cur = sqrt(pow(pos_global[0] - traj_x[index_closest], 2) + pow(pos_global[1] - traj_y[index_closest], 2)); + double div_min = DBL_MAX; + for (int i = index_closest + 1; i < traj_x.size(); i++) { + dist_last = dist_cur; + dist_cur = sqrt(pow(pos_global[0] - traj_x[i], 2) + pow(pos_global[1] - traj_y[i], 2)); + if ((dist_last < dist_target) && (dist_cur > dist_target)) { + // linear interpolation to find the target position + index_target = i; + double xa = traj_x[i - 1] - pos_global[0]; + double ya = traj_y[i - 1] - pos_global[1]; + double xb = traj_x[i] - pos_global[0]; + double yb = traj_y[i] - pos_global[1]; + double ta = (xa - xb)*(xa - xb) + (ya - yb)*(ya - yb); + double tb = -2 * xa*xa + 2 * xa*xb - 2 * ya*ya + 2 * ya*yb; + double tc = xa * xa + ya * ya; + double insqrt = tb * tb - 4 * ta*(tc - dist_target * dist_target); + if (insqrt < 0) { + std::cout << "no solution" << std::endl; + x_target = xb + pos_global[0]; //x_target = xb + pos_global[0]; + y_target = yb + pos_global[1]; // y_target = yb + pos_global[1]; + target_speed = traj_ux[i]; + } + else { + insqrt = sqrt(insqrt); + double t1 = (-tb + insqrt) / (2.0*ta); + double t2 = (-tb - insqrt) / (2.0*ta); + if (t1 >= 0.0 && t1 <= 1.0) { + x_target = (1 - t1)*xa + t1 * xb + pos_global[0]; + y_target = (1 - t1)*ya + t1 * yb + pos_global[1]; + target_speed = traj_ux[i - 1] * (1 - t1) + traj_ux[i] * t1; + } + else if (t2 >= 0.0 && t2 <= 1.0) { + x_target = (1 - t2)*xa + t2 * xb + pos_global[0]; + y_target = (1 - t2)*ya + t2 * yb + pos_global[1]; + target_speed = traj_ux[i - 1] * (1 - t2) + traj_ux[i] * t2; + } + else { + std::cout << "no right solution" << std::endl; + x_target = xb + pos_global[0]; + y_target = yb + pos_global[1]; + target_speed = traj_ux[i]; + } + double temp = sqrt((x_target - pos_global[0])*(x_target - pos_global[0]) + (y_target - pos_global[1])*(y_target - pos_global[1])); + } + break; + } + } + + + return index_target; } -double get_AnglError(double yaw_angle, - const std::vector& traj_x, - const std::vector& traj_y, - int index) { - - if (traj_x.empty() || traj_x.size() == 1) { - return 0; - } - - double yaw_err = atan2(traj_y[index + 1] - traj_y[index], traj_x[index + 1] - traj_x[index]) - yaw_angle; - yaw_err = std::fmod(yaw_err + M_PI, 2*M_PI) - M_PI; +double getTargetAngle(const ChVector<>& pos_global, const std::vector& traj_x, const std::vector& traj_y, + const std::vector& traj_ux, double& target_speed, double cur_speed, double l, double yaw) { + double x_target; + double y_target; + unsigned int index_target = getTargetPos(pos_global, traj_x, traj_y, traj_ux, target_speed, cur_speed, x_target, y_target); + double x_target_COM = cos(yaw)*(x_target - pos_global[0]) + sin(yaw)*(y_target - pos_global[1]); + double y_target_COM = -sin(yaw)*(x_target - pos_global[0]) + cos(yaw)*(y_target - pos_global[1]); + double angle_target = atan(2 * y_target_COM*l / (x_target_COM*x_target_COM + y_target_COM * y_target_COM)); - return yaw_err; + return angle_target; } // ============================================================================= int main(int argc, char* argv[]) { - // ------------------------------ - // Initialize ROS node handle - // ------------------------------ - ros::init(argc, argv, "path_follower"); - ros::NodeHandle node; - - // Declare ROS subscriber to subscribe planner topic - std::string planner_namespace; - node.getParam("system/planner",planner_namespace); - ros::Subscriber planner_sub = node.subscribe(planner_namespace + "/control", 100, plannerCallback); - - std::string chrono_namespace; - node.getParam("system/chrono/namespace", chrono_namespace); - //veh_status message is depricated, use state and control topics and its publishers in future version - ros::Publisher state_pub = node.advertise("/state", 1); - ros::Publisher control_pub = node.advertise("/control", 1); - mavs_msgs::state state_data; - mavs_msgs::control control_data; - - bool gui; - node.getParam("system/chrono/flags/gui", gui); - - // Define variables for ROS parameters server - double step_size; - double tire_step_size; - double x0, y0, z0; // Initial global position - double roll0, pitch0, yaw0, ux0, ax0, sa0; // Initial global orientation - double terrainHeight; - double terrainLength; // size in X direction - double terrainWidth; // size in Y direction - - // Get parameters from ROS Parameter Server - node.getParam("system/params/step_size", step_size); // ROS loop rate and Chrono step size - node.getParam("system/params/tire_step_size", tire_step_size); - // Rigid terrain dimensions - node.getParam("system/chrono/field/h", terrainHeight); - node.getParam("system/chrono/field/l", terrainLength); - node.getParam("system/chrono/field/w", terrainWidth); - - - node.getParam("case/actual/X0/x", x0); // initial x - node.getParam("case/actual/X0/yVal", y0); // initial y - node.getParam("case/actual/X0/z", z0); // initial z - //node.getParam("case/actual/X0/v", v); // lateral velocity - //node.getParam("case/actual/X0/r", r); // lateral velocity - node.getParam("case/actual/X0/theta", pitch0); // initial pitch - node.getParam("case/actual/X0/phi", roll0); // initial roll - node.getParam("case/actual/X0/psi", yaw0); // initial yaw angle - node.getParam("case/actual/X0/sa", sa0); - node.getParam("case/actual/X0/ux", ux0); - node.getParam("case/actual/X0/ax", ax0); - - - // Load chrono vehicle_params - double frict_coeff, rest_coeff; - std::vector centroidLoc, centroidOrientation; - double chassisMass; - std::vector chassisInertia; - std::vector driverLoc, driverOrientation; - std::vector motorBlockDirection, axleDirection; - double driveshaftInertia, differentialBoxInertia, conicalGearRatio, differentialRatio; - std::vector gearRatios; - double steeringLinkMass, steeringLinkRadius, steeringLinkLength; - std::vector steeringLinkInertia; - double pinionRadius, pinionMaxAngle, maxBrakeTorque; - node.getParam("vehicle/chrono/vehicle_params/frict_coeff", frict_coeff); - node.getParam("vehicle/chrono/vehicle_params/rest_coeff", rest_coeff); - node.getParam("vehicle/chrono/vehicle_params/centroidLoc", centroidLoc); - node.getParam("vehicle/chrono/vehicle_params/centroidOrientation", centroidOrientation); - node.getParam("vehicle/chrono/vehicle_params/chassisMass", chassisMass); - node.getParam("vehicle/chrono/vehicle_params/chassisInertia", chassisInertia); - node.getParam("vehicle/chrono/vehicle_params/driverLoc", driverLoc); - node.getParam("vehicle/chrono/vehicle_params/driverOrientation", driverOrientation); - node.getParam("vehicle/chrono/vehicle_params/motorBlockDirection", motorBlockDirection); - node.getParam("vehicle/chrono/vehicle_params/axleDirection", axleDirection); - node.getParam("vehicle/chrono/vehicle_params/driveshaftInertia", driveshaftInertia); - node.getParam("vehicle/chrono/vehicle_params/differentialBoxInertia", differentialBoxInertia); - node.getParam("vehicle/chrono/vehicle_params/conicalGearRatio", conicalGearRatio); - node.getParam("vehicle/chrono/vehicle_params/differentialRatio", differentialRatio); - node.getParam("vehicle/chrono/vehicle_params/gearRatios", gearRatios); - node.getParam("vehicle/chrono/vehicle_params/steeringLinkMass", steeringLinkMass); - node.getParam("vehicle/chrono/vehicle_params/steeringLinkInertia", steeringLinkInertia); - node.getParam("vehicle/chrono/vehicle_params/steeringLinkRadius", steeringLinkRadius); - node.getParam("vehicle/chrono/vehicle_params/steeringLinkLength", steeringLinkLength); - node.getParam("vehicle/chrono/vehicle_params/pinionRadius", pinionRadius); - node.getParam("vehicle/chrono/vehicle_params/pinionMaxAngle", pinionMaxAngle); - node.getParam("vehicle/chrono/vehicle_params/maxBrakeTorque", maxBrakeTorque); - - // Load interpolation parameter - double time_shift; - node.getParam("planner/nloptcontrol_planner/misc/tex", time_shift); - - // --------------------- - // Set up PID controller - // --------------------- - // Velocity PID controller - double Kp_vel, Ki_vel, Kd_vel, Kw_vel, upper_lim_vel, lower_lim_vel; - std::string windup_method_vel; // Anti-windup method - PID vel_controller; - - node.getParam("vehicle/chrono/controller/velocity/Kp", Kp_vel); - node.getParam("vehicle/chrono/controller/velocity/Ki", Ki_vel); - node.getParam("vehicle/chrono/controller/velocity/Kd", Kd_vel); - node.getParam("vehicle/chrono/controller/velocity/Kw", Kw_vel); - node.getParam("vehicle/chrono/controller/velocity/upper_limit", upper_lim_vel); - node.getParam("vehicle/chrono/controller/velocity/lower_limit", lower_lim_vel); - node.getParam("vehicle/chrono/controller/velocity/anti_windup", windup_method_vel); - vel_controller.set_PID(Kp_vel, Ki_vel, Kd_vel, Kw_vel); - vel_controller.set_step_size(step_size); - vel_controller.set_output_limit(lower_lim_vel, upper_lim_vel); - vel_controller.set_windup_metohd(windup_method_vel); - vel_controller.initialize(); - - // Steering PID controller due to distance error - double Kp_str_dist, Ki_str_dist, Kd_str_dist, Kw_str_dist, upper_lim_str_dist, lower_lim_str_dist; - std::string windup_method_str_dist; // Anti-windup method - PID str_controller_dist; - - node.getParam("vehicle/chrono/controller/steering/dist_error/Kp", Kp_str_dist); - node.getParam("vehicle/chrono/controller/steering/dist_error/Ki", Ki_str_dist); - node.getParam("vehicle/chrono/controller/steering/dist_error/Kd", Kd_str_dist); - node.getParam("vehicle/chrono/controller/steering/dist_error/Kw", Kw_str_dist); - node.getParam("vehicle/chrono/controller/steering/dist_error/upper_limit", upper_lim_str_dist); - node.getParam("vehicle/chrono/controller/steering/dist_error/lower_limit", lower_lim_str_dist); - node.getParam("vehicle/chrono/controller/steering/dist_error/anti_windup", windup_method_str_dist); - str_controller_dist.set_PID(Kp_str_dist, Ki_str_dist, Kd_str_dist, Kw_str_dist); - str_controller_dist.set_step_size(step_size); - str_controller_dist.set_output_limit(lower_lim_str_dist, upper_lim_str_dist); - str_controller_dist.set_windup_metohd(windup_method_str_dist); - str_controller_dist.initialize(); - - // Steering PID controller due to distance error - double Kp_str_angl, Ki_str_angl, Kd_str_angl, Kw_str_angl, upper_lim_str_angl, lower_lim_str_angl; - std::string windup_method_str_angl; // Anti-windup method - PID str_controller_angl; - - node.getParam("vehicle/chrono/controller/steering/angle_error/Kp", Kp_str_angl); - node.getParam("vehicle/chrono/controller/steering/angle_error/Ki", Ki_str_angl); - node.getParam("vehicle/chrono/controller/steering/angle_error/Kd", Kd_str_angl); - node.getParam("vehicle/chrono/controller/steering/angle_error/Kw", Kw_str_angl); - node.getParam("vehicle/chrono/controller/steering/angle_error/upper_limit", upper_lim_str_angl); - node.getParam("vehicle/chrono/controller/steering/angle_error/lower_limit", lower_lim_str_angl); - node.getParam("vehicle/chrono/controller/steering/angle_error/anti_windup", windup_method_str_angl); - str_controller_angl.set_PID(Kp_str_angl, Ki_str_angl, Kd_str_angl, Kw_str_angl); - str_controller_angl.set_step_size(step_size); - str_controller_angl.set_output_limit(lower_lim_str_angl, upper_lim_str_angl); - str_controller_angl.set_windup_metohd(windup_method_str_angl); - str_controller_angl.initialize(); - - - // Declare loop rate - ros::Rate loop_rate(1.0/step_size); - - // Set initial vehicle location and orientation - ChVector<> initLoc(x0, y0, z0); - - double t0 = std::cos(yaw0 * 0.5f); - double t1 = std::sin(yaw0 * 0.5f); - double t2 = std::cos(roll0 * 0.5f); - double t3 = std::sin(roll0 * 0.5f); - double t4 = std::cos(pitch0 * 0.5f); - double t5 = std::sin(pitch0 * 0.5f); - - double q0_0 = t0 * t2 * t4 + t1 * t3 * t5; - double q0_1 = t0 * t3 * t4 - t1 * t2 * t5; - double q0_2 = t0 * t2 * t5 + t1 * t3 * t4; - double q0_3 = t1 * t2 * t4 - t0 * t3 * t5; - - ChQuaternion<> initRot(q0_0,q0_1,q0_2,q0_3); - - // wait system loaded - waitForLoaded(node); - - // ------------------------------ - // Create the vehicle and terrain - // ------------------------------ - - // Create the HMMWV vehicle, set parameters, and initialize - HMMWV_Full my_hmmwv; - my_hmmwv.SetContactMethod(contact_method); - my_hmmwv.SetChassisFixed(false); - my_hmmwv.SetInitPosition(ChCoordsys<>(initLoc, initRot)); - my_hmmwv.SetInitFwdVel(ux0); - my_hmmwv.SetPowertrainType(powertrain_model); - my_hmmwv.SetDriveType(drive_type); - my_hmmwv.SetSteeringType(steering_type); - my_hmmwv.SetTireType(tire_model); - my_hmmwv.SetTireStepSize(tire_step_size); - my_hmmwv.SetVehicleStepSize(step_size); - my_hmmwv.Initialize(); - - my_hmmwv.SetChassisVisualizationType(chassis_vis_type); - my_hmmwv.SetSuspensionVisualizationType(suspension_vis_type); - my_hmmwv.SetSteeringVisualizationType(steering_vis_type); - my_hmmwv.SetWheelVisualizationType(wheel_vis_type); - my_hmmwv.SetTireVisualizationType(tire_vis_type); - - // read maximum_steering_angle - double maximum_steering_angle = my_hmmwv.GetVehicle().GetMaxSteeringAngle(); - - // Create the terrain - RigidTerrain terrain(my_hmmwv.GetSystem()); - auto patch = terrain.AddPatch(ChCoordsys<>(ChVector<>(0, 0, terrainHeight - 5), QUNIT), - ChVector<>(terrainLength, terrainWidth, 10)); - patch->SetContactFrictionCoefficient(frict_coeff); - patch->SetContactRestitutionCoefficient(rest_coeff); - patch->SetContactMaterialProperties(2e7f, 0.3f); - patch->SetColor(ChColor(1, 1, 1)); - patch->SetTexture(data_path+"terrain/textures/tile4.jpg", 200, 200); - terrain.Initialize(); - - - // --------------------------------------- - // Create the vehicle Irrlicht application - // --------------------------------------- - - ChVehicleIrrApp app(&my_hmmwv.GetVehicle(), &my_hmmwv.GetPowertrain(), L"Path Follower", - irr::core::dimension2d(800, 640)); - - app.SetHUDLocation(500, 20); - app.AddTypicalLights(irr::core::vector3df(-150.f, -150.f, 200.f), irr::core::vector3df(-150.f, 150.f, 200.f), 100, - 100); - app.AddTypicalLights(irr::core::vector3df(150.f, -150.f, 200.f), irr::core::vector3df(150.0f, 150.f, 200.f), 100, - 100); - app.EnableGrid(false); - app.SetTimestep(step_size); - - // Finalize construction of visualization assets - app.AssetBindAll(); - app.AssetUpdateAll(); - // --------------- - // Simulation loop - // --------------- - - // Initialize simulation frame counter and simulation time - ChRealtimeStepTimer realtime_timer; - - // Vehicle steering angle - double long_velocity = 0.0; - ChVector<> VehicleCOMPos = my_hmmwv.GetVehicle().GetVehicleCOMPos(); - ChQuaternion<> VehicleRot = my_hmmwv.GetVehicle().GetVehicleRot();//global orientation as quaternion - - double q0 = VehicleRot[0]; - double q1 = VehicleRot[1]; - double q2 = VehicleRot[2]; - double q3 = VehicleRot[3]; - double yaw_angle = atan2(2*(q0*q3+q1*q2),1-2*(q2*q2+q3*q3)); - long_velocity = ux0; - // Collect controller output data from modules (for inter-module communication) - double throttle_input = 0; - double steering_input = 0; - double braking_input = 0; - - // to calculate control error: - std::vector x_cal(3, VehicleCOMPos[0]); - std::vector y_cal(3, VehicleCOMPos[1]); - double steering_angle; - - - while (ros::ok()) { - // Get chrono time - double chrono_time = my_hmmwv.GetSystem()->GetChTime(); - - // steering control - if (traj_x.empty() || traj_x.size() == 1) { - steering_angle = 0; - steering_input = 0; - } - else { - int nearest_index = get_nearest_index(VehicleCOMPos, traj_x, traj_y); - double pos_err = get_PosError(VehicleCOMPos, traj_x, traj_y, nearest_index); - double yaw_err = get_AnglError(yaw_angle, traj_x, traj_y, nearest_index); - - steering_angle = str_controller_dist.control(pos_err) + - str_controller_angl.control(yaw_err); - - steering_input = steering_angle / maximum_steering_angle; - steering_input = std::max(-1.0, std::min(1.0, steering_input)); - steering_angle = steering_input * maximum_steering_angle; // steering angle (rad) - } - - // Speed control - // -------------------------- - // interpolation using ALGLIB - // -------------------------- - if (traj_t.size() > 1) { - real_1d_array t_arr, sa_arr, ux_arr; - - t_arr.setcontent(traj_t.size(), &(traj_t[0])); - sa_arr.setcontent(traj_sa.size(), &(traj_sa[0])); - ux_arr.setcontent(traj_ux.size(), &(traj_ux[0])); - - spline1dinterpolant s_ux; - spline1dinterpolant s_sa; - - spline1dbuildlinear(t_arr, ux_arr, s_ux); - traj_ux_interp = spline1dcalc(s_ux, chrono_time+time_shift); - spline1dbuildcubic(t_arr, sa_arr, s_sa); - traj_sa_interp = spline1dcalc(s_sa, chrono_time+time_shift); - } - else if (traj_t.size() == 1) { - std::cout << "traj_size = 0" << std::endl; - traj_ux_interp = traj_ux[0]; - traj_sa_interp = traj_sa[0]; - - } - - - - // Control speed - double ux_err = traj_ux_interp - long_velocity; - double vel_controller_output = vel_controller.control(ux_err); - if (vel_controller_output > 0){ - throttle_input = vel_controller_output; - braking_input = 0; - } - else { - throttle_input = 0; - braking_input = -vel_controller_output; - } - - - - - if(gui) { - app.BeginScene(true, true, irr::video::SColor(255, 140, 161, 192)); - app.DrawAll(); - } - - // Update modules (process inputs from other modules) - terrain.Synchronize(chrono_time); - my_hmmwv.Synchronize(chrono_time, steering_input, braking_input, throttle_input, terrain); - - if(gui) { - app.Synchronize("", steering_input, throttle_input, braking_input); - } - - // Advance simulation for one timestep for all modules - double step = realtime_timer.SuggestSimulationStep(step_size); - terrain.Advance(step); - my_hmmwv.Advance(step); - - if(gui) { - app.Advance(step); - } - - VehicleCOMPos = my_hmmwv.GetVehicle().GetVehicleCOMPos(); - VehicleRot = my_hmmwv.GetVehicle().GetVehicleRot();//global orientation as quaternion - ChVector<> rot_dt = my_hmmwv.GetChassisBody()->GetWvel_loc(); // actual angular speed (expressed in local coords) - ChVector<> VehiclePos = my_hmmwv.GetVehicle().GetVehiclePos(); // gloabal vehicle frame origin location - - // Compute yaw angle - double q0 = VehicleRot[0]; - double q1 = VehicleRot[1]; - double q2 = VehicleRot[2]; - double q3 = VehicleRot[3]; - double yaw_angle = atan2(2*(q0*q3+q1*q2),1-2*(q2*q2+q3*q3)); - - ChVector<> ORI2COM = global2veh(yaw_angle, VehicleCOMPos - VehiclePos); - - ChVector<> VehicleRot_dt = my_hmmwv.GetChassisBody()->GetWvel_loc(); // actual angular speed (expressed in local coords) - ChVector<> VehicleCOMVel_global = my_hmmwv.GetVehicle().GetVehiclePointVelocity(ORI2COM); // vehicle COM velocity (m/s) - ChVector<> VehicleCOMAcc = my_hmmwv.GetVehicle().GetVehicleAcceleration(ORI2COM); // vehicle COM acceleration (m/s^2) - VehicleCOMAcc[0] = std::max(-1.5, std::min(1.5, VehicleCOMAcc[0])); // let vehicle acceleration bounded in [-1.5, 1.5] (temporary solution) - - ChVector<> VehicleCOMVel = global2veh(yaw_angle, VehicleCOMVel_global); - - // Get vertical tire force - std::vector TireForceVertical; - for (int i = 0; i < 4; i++) { - ChVector<> TireForce = my_hmmwv.GetTire(i)->ReportTireForce(&terrain).force; - TireForceVertical.push_back(TireForce[2]); - } - long_velocity = VehicleCOMVel[0]; - // Update vehicle state - node.setParam("/state/t", chrono_time); - node.setParam("/state/x", VehicleCOMPos[0]); // global x position (m) - node.setParam("/state/y", VehicleCOMPos[1]); // global y position (m) - node.setParam("/state/v", VehicleCOMVel[1]); //// lateral velocity (m/s) - node.setParam("/state/r", VehicleRot_dt[2]); //// yaw rate (rad/s) - node.setParam("/state/psi", yaw_angle); // global heading angle (yaw angle) (rad) - node.setParam("/state/sa", steering_angle); // steering angle at the tire (rad) - node.setParam("/state/ux", VehicleCOMVel[0]); //// longitudinal velocity (vehicle frame) (m/s) - node.setParam("/state/ax", VehicleCOMAcc[0]); //// longitudinal acceleration (vehicle frame) (m/s^2) - node.setParam("/control/thr", throttle_input); - node.setParam("/control/brk", braking_input); - node.setParam("/control/str", steering_input); - - // In future we will shift to state and control variables - // Update state and control data - state_data.t = chrono_time; // time in chrono simulation - state_data.x = VehicleCOMPos[0]; - state_data.y = VehicleCOMPos[1]; - state_data.ux = VehicleCOMVel[0]; - state_data.v = VehicleCOMVel[1]; - state_data.ax = VehicleCOMAcc[0]; - state_data.psi = yaw_angle; // yaw angle (rad) - state_data.r = VehicleRot_dt[2];// yaw rate (rad/s) - state_data.sa = steering_angle; // steering angle at the tire (rad) - control_data.t = chrono_time; - control_data.thrt_in = throttle_input; // throttle input in the range [0,+1] - control_data.brk_in = braking_input; // braking input in the range [0,+1] - control_data.str_in = steering_input; // steeering input in the range [-1,+1] - - state_pub.publish(state_data); - control_pub.publish(control_data); - if(gui) { - app.EndScene(); - } - - ros::spinOnce(); - // loop_rate.sleep(); - } - - return 0; + // ------------------------------ + // Initialize ROS node handle + // ------------------------------ + ros::init(argc, argv, "path_follower"); + ros::NodeHandle node; + + // Declare ROS subscriber to subscribe planner topic + std::string planner_namespace; + node.getParam("system/planner", planner_namespace); + ros::Subscriber planner_sub = node.subscribe(planner_namespace + "/control", 100, plannerCallback); + + std::string chrono_namespace; + node.getParam("system/chrono/namespace", chrono_namespace); + //veh_status message is depricated, use state and control topics and its publishers in future version + ros::Publisher state_pub = node.advertise("/state", 1); + ros::Publisher control_pub = node.advertise("/control", 1); + mavs_msgs::state state_data; + mavs_msgs::control control_data; + + bool gui; + node.getParam("system/chrono/flags/gui", gui); + + // Define variables for ROS parameters server + double step_size; + double tire_step_size; + double x0, y0, z0; // Initial global position + double roll0, pitch0, yaw0, ux0, ax0, sa0; // Initial global orientation + double terrainHeight; + double terrainLength; // size in X direction + double terrainWidth; // size in Y direction + + // Get parameters from ROS Parameter Server + node.getParam("system/params/step_size", step_size); // ROS loop rate and Chrono step size + node.getParam("system/params/tire_step_size", tire_step_size); + // Rigid terrain dimensions + node.getParam("system/chrono/field/h", terrainHeight); + node.getParam("system/chrono/field/l", terrainLength); + node.getParam("system/chrono/field/w", terrainWidth); + + + node.getParam("case/actual/X0/x", x0); // initial x + node.getParam("case/actual/X0/yVal", y0); // initial y + node.getParam("case/actual/X0/z", z0); // initial z + //node.getParam("case/actual/X0/v", v); // lateral velocity + //node.getParam("case/actual/X0/r", r); // lateral velocity + node.getParam("case/actual/X0/theta", pitch0); // initial pitch + node.getParam("case/actual/X0/phi", roll0); // initial roll + node.getParam("case/actual/X0/psi", yaw0); // initial yaw angle + node.getParam("case/actual/X0/sa", sa0); + node.getParam("case/actual/X0/ux", ux0); + node.getParam("case/actual/X0/ax", ax0); + + + // Load chrono vehicle_params + double frict_coeff, rest_coeff; + std::vector centroidLoc, centroidOrientation; + double chassisMass; + std::vector chassisInertia; + std::vector driverLoc, driverOrientation; + std::vector motorBlockDirection, axleDirection; + double driveshaftInertia, differentialBoxInertia, conicalGearRatio, differentialRatio; + std::vector gearRatios; + double steeringLinkMass, steeringLinkRadius, steeringLinkLength; + std::vector steeringLinkInertia; + double pinionRadius, pinionMaxAngle, maxBrakeTorque; + node.getParam("vehicle/chrono/vehicle_params/frict_coeff", frict_coeff); + node.getParam("vehicle/chrono/vehicle_params/rest_coeff", rest_coeff); + node.getParam("vehicle/chrono/vehicle_params/centroidLoc", centroidLoc); + node.getParam("vehicle/chrono/vehicle_params/centroidOrientation", centroidOrientation); + node.getParam("vehicle/chrono/vehicle_params/chassisMass", chassisMass); + node.getParam("vehicle/chrono/vehicle_params/chassisInertia", chassisInertia); + node.getParam("vehicle/chrono/vehicle_params/driverLoc", driverLoc); + node.getParam("vehicle/chrono/vehicle_params/driverOrientation", driverOrientation); + node.getParam("vehicle/chrono/vehicle_params/motorBlockDirection", motorBlockDirection); + node.getParam("vehicle/chrono/vehicle_params/axleDirection", axleDirection); + node.getParam("vehicle/chrono/vehicle_params/driveshaftInertia", driveshaftInertia); + node.getParam("vehicle/chrono/vehicle_params/differentialBoxInertia", differentialBoxInertia); + node.getParam("vehicle/chrono/vehicle_params/conicalGearRatio", conicalGearRatio); + node.getParam("vehicle/chrono/vehicle_params/differentialRatio", differentialRatio); + node.getParam("vehicle/chrono/vehicle_params/gearRatios", gearRatios); + node.getParam("vehicle/chrono/vehicle_params/steeringLinkMass", steeringLinkMass); + node.getParam("vehicle/chrono/vehicle_params/steeringLinkInertia", steeringLinkInertia); + node.getParam("vehicle/chrono/vehicle_params/steeringLinkRadius", steeringLinkRadius); + node.getParam("vehicle/chrono/vehicle_params/steeringLinkLength", steeringLinkLength); + node.getParam("vehicle/chrono/vehicle_params/pinionRadius", pinionRadius); + node.getParam("vehicle/chrono/vehicle_params/pinionMaxAngle", pinionMaxAngle); + node.getParam("vehicle/chrono/vehicle_params/maxBrakeTorque", maxBrakeTorque); + + // Load interpolation parameter + double time_shift; + node.getParam("planner/nloptcontrol_planner/misc/tex", time_shift); + time_shift = 0.1; + + // --------------------- + // Set up PID controller + // --------------------- + // Velocity PID controller + double Kp_vel, Ki_vel, Kd_vel, Kw_vel, upper_lim_vel, lower_lim_vel; + std::string windup_method_vel; // Anti-windup method + PID vel_controller; + + node.getParam("vehicle/chrono/controller/velocity/Kp", Kp_vel); + node.getParam("vehicle/chrono/controller/velocity/Ki", Ki_vel); + node.getParam("vehicle/chrono/controller/velocity/Kd", Kd_vel); + node.getParam("vehicle/chrono/controller/velocity/Kw", Kw_vel); + node.getParam("vehicle/chrono/controller/velocity/upper_limit", upper_lim_vel); + node.getParam("vehicle/chrono/controller/velocity/lower_limit", lower_lim_vel); + node.getParam("vehicle/chrono/controller/velocity/anti_windup", windup_method_vel); + vel_controller.set_PID(Kp_vel, Ki_vel, Kd_vel, Kw_vel); + vel_controller.set_step_size(step_size); + vel_controller.set_output_limit(lower_lim_vel, upper_lim_vel); + vel_controller.set_windup_metohd(windup_method_vel); + vel_controller.initialize(); + + // Steering PID controller due to distance error + double Kp_str_dist, Ki_str_dist, Kd_str_dist, Kw_str_dist, upper_lim_str_dist, lower_lim_str_dist; + std::string windup_method_str_dist; // Anti-windup method + PID str_controller_dist; + + node.getParam("vehicle/chrono/controller/steering/dist_error/Kp", Kp_str_dist); + node.getParam("vehicle/chrono/controller/steering/dist_error/Ki", Ki_str_dist); + node.getParam("vehicle/chrono/controller/steering/dist_error/Kd", Kd_str_dist); + node.getParam("vehicle/chrono/controller/steering/dist_error/Kw", Kw_str_dist); + node.getParam("vehicle/chrono/controller/steering/dist_error/upper_limit", upper_lim_str_dist); + node.getParam("vehicle/chrono/controller/steering/dist_error/lower_limit", lower_lim_str_dist); + node.getParam("vehicle/chrono/controller/steering/dist_error/anti_windup", windup_method_str_dist); + str_controller_dist.set_PID(Kp_str_dist, Ki_str_dist, Kd_str_dist, Kw_str_dist); + str_controller_dist.set_step_size(step_size); + str_controller_dist.set_output_limit(lower_lim_str_dist, upper_lim_str_dist); + str_controller_dist.set_windup_metohd(windup_method_str_dist); + str_controller_dist.initialize(); + + // Steering PID controller due to distance error + double Kp_str_angl, Ki_str_angl, Kd_str_angl, Kw_str_angl, upper_lim_str_angl, lower_lim_str_angl; + std::string windup_method_str_angl; // Anti-windup method + PID str_controller_angl; + + node.getParam("vehicle/chrono/controller/steering/angle_error/Kp", Kp_str_angl); + node.getParam("vehicle/chrono/controller/steering/angle_error/Ki", Ki_str_angl); + node.getParam("vehicle/chrono/controller/steering/angle_error/Kd", Kd_str_angl); + node.getParam("vehicle/chrono/controller/steering/angle_error/Kw", Kw_str_angl); + node.getParam("vehicle/chrono/controller/steering/angle_error/upper_limit", upper_lim_str_angl); + node.getParam("vehicle/chrono/controller/steering/angle_error/lower_limit", lower_lim_str_angl); + node.getParam("vehicle/chrono/controller/steering/angle_error/anti_windup", windup_method_str_angl); + str_controller_angl.set_PID(Kp_str_angl, Ki_str_angl, Kd_str_angl, Kw_str_angl); + str_controller_angl.set_step_size(step_size); + str_controller_angl.set_output_limit(lower_lim_str_angl, upper_lim_str_angl); + str_controller_angl.set_windup_metohd(windup_method_str_angl); + str_controller_angl.initialize(); + + + // Declare loop rate + ros::Rate loop_rate(1.0 / step_size); + + // Set initial vehicle location and orientation + ChVector<> initLoc(x0, y0, z0); + + double t0 = std::cos(yaw0 * 0.5f); + double t1 = std::sin(yaw0 * 0.5f); + double t2 = std::cos(roll0 * 0.5f); + double t3 = std::sin(roll0 * 0.5f); + double t4 = std::cos(pitch0 * 0.5f); + double t5 = std::sin(pitch0 * 0.5f); + + double q0_0 = t0 * t2 * t4 + t1 * t3 * t5; + double q0_1 = t0 * t3 * t4 - t1 * t2 * t5; + double q0_2 = t0 * t2 * t5 + t1 * t3 * t4; + double q0_3 = t1 * t2 * t4 - t0 * t3 * t5; + + ChQuaternion<> initRot(q0_0, q0_1, q0_2, q0_3); + + // ------------------------------ + // Create the vehicle and terrain + // ------------------------------ + + // Create the HMMWV vehicle, set parameters, and initialize + HMMWV_Full my_hmmwv; + my_hmmwv.SetContactMethod(contact_method); + my_hmmwv.SetChassisFixed(false); + my_hmmwv.SetInitPosition(ChCoordsys<>(initLoc, initRot)); + my_hmmwv.SetInitFwdVel(ux0); + my_hmmwv.SetPowertrainType(powertrain_model); + my_hmmwv.SetDriveType(drive_type); + my_hmmwv.SetSteeringType(steering_type); + my_hmmwv.SetTireType(tire_model); + my_hmmwv.SetTireStepSize(tire_step_size); + my_hmmwv.SetVehicleStepSize(step_size); + my_hmmwv.Initialize(); + + my_hmmwv.SetChassisVisualizationType(chassis_vis_type); + my_hmmwv.SetSuspensionVisualizationType(suspension_vis_type); + my_hmmwv.SetSteeringVisualizationType(steering_vis_type); + my_hmmwv.SetWheelVisualizationType(wheel_vis_type); + my_hmmwv.SetTireVisualizationType(tire_vis_type); + + // read maximum_steering_angle + double maximum_steering_angle = my_hmmwv.GetVehicle().GetMaxSteeringAngle(); + + // Create the terrain + //RigidTerrain terrain(terrainHeight - 5, frict_coeff); + RigidTerrain terrain(my_hmmwv.GetSystem()); + auto patch = terrain.AddPatch(ChCoordsys<>(ChVector<>(0, 0, terrainHeight - 5), QUNIT), + ChVector<>(terrainLength, terrainWidth, 10)); + patch->SetContactFrictionCoefficient(frict_coeff); + patch->SetContactRestitutionCoefficient(rest_coeff); + patch->SetContactMaterialProperties(2e7f, 0.3f); + patch->SetColor(ChColor(1, 1, 1)); + patch->SetTexture(data_path + "terrain/textures/tile4.jpg", 200, 200); + terrain.Initialize(); + + + // --------------------------------------- + // Create the vehicle Irrlicht application + // --------------------------------------- + + ChVehicleIrrApp app(&my_hmmwv.GetVehicle(), &my_hmmwv.GetPowertrain(), L"Path Follower", + irr::core::dimension2d(800, 640)); + + app.SetHUDLocation(500, 20); + app.AddTypicalLights(irr::core::vector3df(-150.f, -150.f, 200.f), irr::core::vector3df(-150.f, 150.f, 200.f), 100, + 100); + app.AddTypicalLights(irr::core::vector3df(150.f, -150.f, 200.f), irr::core::vector3df(150.0f, 150.f, 200.f), 100, + 100); + app.EnableGrid(false); + app.SetTimestep(step_size); + + // Finalize construction of visualization assets + app.AssetBindAll(); + app.AssetUpdateAll(); + // --------------- + // Simulation loop + // --------------- + + // Initialize simulation frame counter and simulation time + ChRealtimeStepTimer realtime_timer; + + // Vehicle steering angle + double long_velocity = 0.0; + ChVector<> VehicleCOMPos = my_hmmwv.GetVehicle().GetVehicleCOMPos(); + ChQuaternion<> VehicleRot = my_hmmwv.GetVehicle().GetVehicleRot();//global orientation as quaternion + long_velocity = my_hmmwv.GetVehicle().GetVehicleSpeedCOM(); + double yaw_angle = VehicleRot.Q_to_Euler123()[2]; + + + + // Collect controller output data from modules (for inter-module communication) + double throttle_input = 0; + double steering_input = 0; + double braking_input = 0; + + // to calculate control error: + std::vector x_cal(3, VehicleCOMPos[0]); + std::vector y_cal(3, VehicleCOMPos[1]); + double steering_angle; + + + // find lr and lf + ChVector<> front_pos1 = my_hmmwv.GetVehicle().GetWheelPos(0); + ChVector<> front_pos2 = my_hmmwv.GetVehicle().GetWheelPos(1); + ChVector<> rear_pos1 = my_hmmwv.GetVehicle().GetWheelPos(2); + ChVector<> rear_pos2 = my_hmmwv.GetVehicle().GetWheelPos(3); + double front_x = (front_pos1[0] + front_pos2[0]) / 2.; + double front_y = (front_pos1[1] + front_pos2[1]) / 2.; + double rear_x = (rear_pos1[0] + rear_pos2[0]) / 2.; + double rear_y = (rear_pos1[1] + rear_pos2[1]) / 2.; + double front2rear = sqrt(pow(rear_x - front_x, 2) + pow(rear_y - front_y, 2)); + + // wait system loaded + waitForLoaded(node); + while (ros::ok()) { + // Get chrono time + double chrono_time = my_hmmwv.GetSystem()->GetChTime(); + + // steering control + if (traj_x.empty() || traj_x.size() == 1) { + steering_angle = 0; + steering_input = 0; + } + else { + front_pos1 = my_hmmwv.GetVehicle().GetWheelPos(0); + front_pos2 = my_hmmwv.GetVehicle().GetWheelPos(1); + rear_pos1 = my_hmmwv.GetVehicle().GetWheelPos(2); + rear_pos2 = my_hmmwv.GetVehicle().GetWheelPos(3); + front_x = (front_pos1[0] + front_pos2[0]) / 2.; + front_y = (front_pos1[1] + front_pos2[1]) / 2.; + rear_x = (rear_pos1[0] + rear_pos2[0]) / 2.; + rear_y = (rear_pos1[1] + rear_pos2[1]) / 2.; + front2rear = sqrt(pow(rear_x - front_x, 2) + pow(rear_y - front_y, 2)); + traj_sa_interp = 1.0*getTargetAngle(VehicleCOMPos, traj_x, traj_y, traj_ux, traj_ux_interp, long_velocity, front2rear, yaw_angle); + traj_ux_interp = std::max(0.0, traj_ux_interp); + + // steering rate saturation + /*if (((traj_sa_interp - steering_input*maximum_steering_angle) / step_size) > 1.5) { + traj_sa_interp = (steering_input*maximum_steering_angle + 1.5*step_size); + } + else if (((steering_input*maximum_steering_angle - traj_sa_interp) / step_size) < -1.5) { + traj_sa_interp = (steering_input*maximum_steering_angle - 1.5*step_size); + }*/ + // simple low pass filter + double alpha = 1.0; + steering_input = (1.0 - alpha) * steering_input + alpha * traj_sa_interp / maximum_steering_angle; + steering_input = std::max(-1.0, std::min(1.0, steering_input)); + steering_angle = steering_input * maximum_steering_angle; // steering angle (rad) + } + + + // Control speed + double ux_err = traj_ux_interp - long_velocity; + double vel_controller_output = vel_controller.control(ux_err); + if (vel_controller_output > 0) { + throttle_input = vel_controller_output; + braking_input = 0; + } + else { + throttle_input = 0; + braking_input = -vel_controller_output; + } + + + if (gui) { + app.BeginScene(true, true, irr::video::SColor(255, 140, 161, 192)); + app.DrawAll(); + } + + // Update modules (process inputs from other modules) + terrain.Synchronize(chrono_time); + my_hmmwv.Synchronize(chrono_time, steering_input, braking_input, throttle_input, terrain); + + if (gui) { + app.Synchronize("", steering_input, throttle_input, braking_input); + } + + // Advance simulation for one timestep for all modules + double step = realtime_timer.SuggestSimulationStep(step_size); + terrain.Advance(step); + my_hmmwv.Advance(step); + + if (gui) { + app.Advance(step); + } + + VehicleCOMPos = my_hmmwv.GetVehicle().GetVehicleCOMPos(); + VehicleRot = my_hmmwv.GetVehicle().GetVehicleRot();//global orientation as quaternion + ChVector<> rot_dt = my_hmmwv.GetChassisBody()->GetWvel_loc(); // actual angular speed (expressed in local coords) + ChVector<> VehiclePos = my_hmmwv.GetVehicle().GetVehiclePos(); // gloabal vehicle frame origin location + + // Compute yaw angle + yaw_angle = VehicleRot.Q_to_Euler123()[2]; + + ChVector<> ORI2COM = global2veh(yaw_angle, VehicleCOMPos - VehiclePos); + + ChVector<> VehicleRot_dt = my_hmmwv.GetChassisBody()->GetWvel_loc(); // actual angular speed (expressed in local coords) + ChVector<> VehicleCOMVel_global = my_hmmwv.GetVehicle().GetVehiclePointVelocity(ORI2COM); // vehicle COM velocity (m/s) + ChVector<> VehicleCOMAcc = my_hmmwv.GetVehicle().GetVehicleAcceleration(ORI2COM); // vehicle COM acceleration (m/s^2) + VehicleCOMAcc[0] = std::max(-1.5, std::min(1.5, VehicleCOMAcc[0])); // let vehicle acceleration bounded in [-1.5, 1.5] (temporary solution) + + ChVector<> VehicleCOMVel = global2veh(yaw_angle, VehicleCOMVel_global); + + // Get vertical tire force + std::vector TireForceVertical; + for (int i = 0; i < 4; i++) { + ChVector<> TireForce = my_hmmwv.GetTire(i)->ReportTireForce(&terrain).force; + TireForceVertical.push_back(TireForce[2]); + } + + // Update vehicle state + node.setParam("/state/t", chrono_time); + node.setParam("/state/x", VehicleCOMPos[0]); // global x position (m) + node.setParam("/state/y", VehicleCOMPos[1]); // global y position (m) + node.setParam("/state/v", VehicleCOMVel[1]); //// lateral velocity (m/s) + node.setParam("/state/r", VehicleRot_dt[2]); //// yaw rate (rad/s) + node.setParam("/state/psi", yaw_angle); // global heading angle (yaw angle) (rad) + node.setParam("/state/sa", steering_angle); // steering angle at the tire (rad) + node.setParam("/state/ux", VehicleCOMVel[0]); //// longitudinal velocity (vehicle frame) (m/s) + node.setParam("/state/ax", VehicleCOMAcc[0]); //// longitudinal acceleration (vehicle frame) (m/s^2) + node.setParam("/control/thr", throttle_input); + node.setParam("/control/brk", braking_input); + node.setParam("/control/str", steering_input); + + // In future we will shift to state and control variables + // Update state and control data + state_data.t = chrono_time; // time in chrono simulation + state_data.x = VehicleCOMPos[0]; + state_data.y = VehicleCOMPos[1]; + state_data.ux = VehicleCOMVel[0]; + state_data.v = VehicleCOMVel[1]; + state_data.ax = VehicleCOMAcc[0]; + state_data.psi = yaw_angle; // yaw angle (rad) + state_data.r = VehicleRot_dt[2];// yaw rate (rad/s) + state_data.sa = steering_angle; // steering angle at the tire (rad) + control_data.thrt_in = throttle_input; // throttle input in the range [0,+1] + control_data.brk_in = braking_input; // braking input in the range [0,+1] + control_data.str_in = steering_input; // steeering input in the range [-1,+1] + + state_pub.publish(state_data); + control_pub.publish(control_data); + if (gui) { + app.EndScene(); + } + + ros::spinOnce(); + // loop_rate.sleep(); + } + + return 0; } diff --git a/ros/src/models/chrono/ros_chrono/src/trajectory_follower.cpp b/ros/src/models/chrono/ros_chrono/src/trajectory_follower.cpp index b0967e89..b4c58aec 100755 --- a/ros/src/models/chrono/ros_chrono/src/trajectory_follower.cpp +++ b/ros/src/models/chrono/ros_chrono/src/trajectory_follower.cpp @@ -222,7 +222,7 @@ int main(int argc, char* argv[]) { // Load interpolation parameter double time_shift; node.getParam("planner/nloptcontrol_planner/misc/tex", time_shift); - + //time_shift = 0.1; // --------------------- // Set up PID controller // --------------------- @@ -276,6 +276,8 @@ int main(int argc, char* argv[]) { HMMWV_Full my_hmmwv; my_hmmwv.SetContactMethod(contact_method); my_hmmwv.SetChassisFixed(false); + my_hmmwv.SetInitPosition(ChCoordsys<>(initLoc, initRot)); + my_hmmwv.SetInitFwdVel(ux0); my_hmmwv.SetPowertrainType(powertrain_model); my_hmmwv.SetDriveType(drive_type); my_hmmwv.SetSteeringType(steering_type); @@ -367,10 +369,10 @@ int main(int argc, char* argv[]) { // steering input // steering rate saturation if (((traj_sa_interp - steering_input*maximum_steering_angle) / step_size) > 1.5) { - traj_sa_interp = (traj_sa_interp - 1.5*step_size); + traj_sa_interp = (steering_input*maximum_steering_angle + 1.5*step_size); } else if (((steering_input*maximum_steering_angle - traj_sa_interp) / step_size) < -1.5) { - traj_sa_interp = (traj_sa_interp + 1.5*step_size); + traj_sa_interp = (steering_input*maximum_steering_angle - 1.5*step_size); } // simple low pass filter double alpha = 0.4; @@ -423,12 +425,7 @@ int main(int argc, char* argv[]) { double steering_angle = steering_input * maximum_steering_angle; // steering angle (rad) // Compute yaw angle - double q0 = VehicleRot[0]; - double q1 = VehicleRot[1]; - double q2 = VehicleRot[2]; - double q3 = VehicleRot[3]; - double yaw_angle = atan2(2*(q0*q3+q1*q2),1-2*(q2*q2+q3*q3)); - + double yaw_angle = VehicleRot.Q_to_Euler123()[2]; ChVector<> ORI2COM = global2veh(yaw_angle, VehicleCOMPos - VehiclePos); ChVector<> VehicleRot_dt = my_hmmwv.GetChassisBody()->GetWvel_loc(); // actual angular speed (expressed in local coords) diff --git a/ros/src/models/chrono/traj_gen_chrono/CMakeLists.txt b/ros/src/models/chrono/traj_gen_chrono/CMakeLists.txt index af3ebbe2..2e63dd0f 100644 --- a/ros/src/models/chrono/traj_gen_chrono/CMakeLists.txt +++ b/ros/src/models/chrono/traj_gen_chrono/CMakeLists.txt @@ -79,10 +79,10 @@ find_package( # ) ## Generate added messages and services with any dependencies listed here -generate_messages( - DEPENDENCIES - std_msgs -) +# generate_messages( +# DEPENDENCIES +# std_msgs +# ) ################################################ ## Declare ROS dynamic reconfigure parameters ## @@ -115,9 +115,7 @@ generate_messages( ## DEPENDS: system dependencies of this project that dependent projects also need catkin_package( # INCLUDE_DIRS include -# LIBRARIES ros_chrono_msgs CATKIN_DEPENDS roscpp rospy std_msgs -# DEPENDS system_lib ) ########### @@ -145,7 +143,6 @@ endif() ## Declare a C++ library # add_library(${PROJECT_NAME} -# src/${PROJECT_NAME}/ros_chrono_msgs.cpp # ) ## Add cmake target dependencies of the library @@ -156,7 +153,6 @@ endif() ## Declare a C++ executable ## With catkin_make all packages are built within a single CMake context ## The recommended prefix ensures that target names across packages don't collide -# add_executable(${PROJECT_NAME}_node src/ros_chrono_msgs_node.cpp) add_executable(traj_gen_chrono src/traj_gen_chrono.cpp) add_executable(path_gen_chrono src/path_gen_chrono.cpp) add_executable(vel_gen_chrono src/vel_gen_chrono.cpp) @@ -235,7 +231,6 @@ target_link_libraries(vel_gen_chrono ############# ## Add gtest based cpp test target and link libraries -# catkin_add_gtest(${PROJECT_NAME}-test test/test_ros_chrono_msgs.cpp) # if(TARGET ${PROJECT_NAME}-test) # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) # endif() diff --git a/ros/src/models/gazebo/vehicle_description/meshes/hokuyo.dae b/ros/src/models/gazebo/vehicle_description/meshes/hokuyo.dae new file mode 100644 index 00000000..aad99509 --- /dev/null +++ b/ros/src/models/gazebo/vehicle_description/meshes/hokuyo.dae @@ -0,0 +1,276 @@ + + + +Blender User +Blender 2.64.0 r51232 + +2013-03-22T08:19:53 +2013-03-22T08:19:53 + +Z_UP + + + + + + +49.13434 +1.777778 +0.1 +100 + + + + + + + + + +1 1 1 +1 +0 +0.00111109 + + + + +0.000999987 +0 +1 +1 +1 +1 +1 +2 +0 +1 +1 +1 +1 +1 +0 +2880 +2 +30.002 +1.000799 +0.04999995 +29.99998 +1 +2 +0 +0 +1 +1 +1 +1 +8192 +1 +1 +0 +1 +1 +1 +3 +0 +0 +0 +0 +45 +0 +1 +1 +1 +3 +0.15 +75 +1 +1 +0 +1 +1 +0 + + + + + + + + + + + +0 0 0 1 + + +0 0 0 1 + + +0.020312 0.020312 0.020312 1 + + +0.25 0.25 0.25 1 + + +12 + + +1 + + + + + +1 + + + + + +1 + + + + + + + + +0 0 0 1 + + +0 0 0 1 + + +0.695112 0.695112 0.695112 1 + + +0.0625 0.0625 0.0625 1 + + +0 + + +1 + + + + + +1 + + + + + +1 + + + + + + + + + + + + + + + + + +-0.02213996 0.005949974 -0.004869997 -0.02213996 0.005949974 0.004869997 -0.02164 0.009949982 -0.004999995 -0.02164 0.009949982 -0.005999982 -0.02164 0.009949982 0.004999995 -0.02164 0.009949982 0.005999982 -0.02149999 0.009949982 -0.006499946 -0.02149999 0.009949982 0.006499946 -0.02113997 0.009949982 -0.006869971 -0.02113997 0.009949982 0.006869971 -0.02063995 0.005949974 0.006999969 -0.02063995 0.009949982 -0.006999969 -0.02063995 0.009949982 0.006999969 -0.01979994 0.009949982 -0.006999969 -0.01979994 0.005949974 -0.006999969 -0.01979994 0.005949974 0.006999969 -0.01979994 0.009949982 0.006999969 -0.01838999 0.005949974 0.01014 -0.02063995 0.005949974 -0.006999969 -0.02113997 0.005949974 0.006869971 -0.02113997 0.005949974 -0.006869971 -0.02149999 0.005949974 0.006499946 -0.02149999 0.005949974 -0.006499946 -0.02164 0.005949974 0.005999982 -0.02164 0.005949974 0.004999995 -0.02164 0.005949974 -0.004999995 -0.02164 0.005949974 -0.005999982 -0.01920998 0.01990997 0.004999995 -0.01920998 0.01990997 -0.004999995 -0.005279958 0.02695 -0.01798999 -0.009719967 0.02695 -0.01595997 -0.01014 0.02695 -0.01576995 -0.01365 0.02695 -0.01273 -0.01416999 0.02695 -0.01227998 -0.01655995 0.02695 -0.008569955 -0.01705998 0.02695 -0.007789969 -0.01822996 0.02695 -0.003779947 -0.01855999 0.02695 -0.00266999 -0.01855999 0.02695 0.00127995 -0.01855999 0.02695 0.00266999 -0.01750999 0.02695 0.006229996 -0.01705998 0.02695 0.007789969 -0.01516997 0.02695 0.01071995 -0.01416999 0.02695 0.01227998 -0.01170998 0.02695 0.01440995 -0.01014 0.02695 0.01576995 -0.007389962 0.02695 0.01703 -0.005279958 0.02695 0.01798999 -0.002529978 0.02695 0.01838999 0 0.02695 0.01874995 0.002529978 0.02695 0.01838999 0.005279958 0.02695 0.01798999 0.007389962 0.02695 0.01703 0.01014 0.02695 0.01576995 0.01170998 0.02695 0.01440995 0.01416999 0.02695 0.01227998 0.01516997 0.02695 0.01071995 0.01705998 0.02695 0.007789969 0.01750999 0.02695 0.006229996 0.01855999 0.02695 0.00266999 0.01855999 0.02695 0.00127995 0.01855999 0.02695 -0.00266999 0.01822996 0.02695 -0.003779947 0.01705998 0.02695 -0.007789969 0.01655995 0.02695 -0.008569955 0.01416999 0.02695 -0.01227998 0.01365 0.02695 -0.01273 0.01014 0.02695 -0.01576995 0.009719967 0.02695 -0.01595997 0.005279958 0.02695 -0.01798999 0.005049943 0.02695 -0.01801997 -0.005049943 0.02695 -0.01801997 0 0.02695 -0.01874995 -0.01885998 0.02594995 0.001289963 -0.01850998 0.02594995 -0.003849983 -0.02039998 0.009949982 -0.004999995 -0.02039998 0.009949982 0.004999995 -0.01848 0.02594995 0.003999948 -0.01836997 0.02572995 0.004629969 -0.01840996 0.02588999 0.004329979 -0.01838999 0.02579998 0.004489958 -0.01835 0.02544999 0.004859983 -0.01838999 0.02494996 0.004999995 -0.01835995 0.02517998 0.004969954 -0.02164 0.02494996 0.004999995 -0.02164 0.02544999 0.004869997 -0.02188998 0.02537995 0.004869997 -0.02206999 0.02519994 0.004869997 -0.02213996 0.02494996 0.004869997 -0.02164 0.02581995 0.004499971 -0.02206999 0.02569997 0.004499971 -0.02238994 0.02537995 0.004499971 -0.02249997 0.02494996 0.004499971 -0.02164 0.02594995 0.003999948 -0.02213996 0.02581995 0.003999948 -0.02263998 0.02494996 0.003999948 -0.02249997 0.02544999 0.003999948 -0.02213996 0.02581995 -0.003999948 -0.02249997 0.02544999 -0.003999948 -0.02263998 0.02494996 -0.003999948 -0.02206999 0.02569997 -0.004499971 -0.02188998 0.02537995 -0.004869997 -0.02238994 0.02537995 -0.004499971 -0.02249997 0.02494996 -0.004499971 -0.02206999 0.02519994 -0.004869997 -0.02213996 0.02494996 -0.004869997 -0.01838999 0.02494996 -0.004999995 -0.02164 0.02494996 -0.004999995 -0.01835 0.02555996 -0.004789948 -0.01835995 0.02526998 -0.004949986 -0.01835 0.02543997 -0.00484997 -0.01836997 0.02577996 -0.004559993 -0.02164 0.02544999 -0.004869997 -0.02164 0.02581995 -0.004499971 -0.01848 0.02594995 -0.003999948 -0.02164 0.02594995 -0.003999948 -0.01841998 0.02590996 -0.004269957 -0.02001994 0.01871997 -0.004999995 -0.01986998 0.01879996 -0.004999995 -0.02025997 0.01844996 -0.004999995 -0.02039998 0.01794999 -0.004999995 -0.02037996 0.01813995 -0.004999995 -0.02039998 0.01794999 0.004999995 -0.02033996 0.01826995 0.004999995 -0.01993995 0.01877999 0.004999995 -0.01936 0.01894998 0.004999995 -0.01962 0.01892 0.004999995 -0.01879996 0.01894998 0.006679952 -0.01845997 0.01894998 0.007699966 -0.01936 0.01894998 -0.004999995 -0.01971 0.01888996 -0.004999995 -0.01845997 0.01894998 -0.007699966 -0.01668 0.01894998 -0.01102995 -0.01141995 0.01894998 -0.01641994 -7.8e-4 0.01894998 -0.01997995 0 0.01894998 -0.01993995 0.002989947 0.01894998 -0.01976996 0.01315999 0.01894998 -0.01505994 0.01454997 0.01894998 -0.01358997 0.01576 0.01894998 -0.01230996 0.01990997 0.01894998 0.001369953 0.01990997 0.01894998 -0.001889944 0.01919996 0.01894998 0.005609989 0.01779997 0.01894998 0.009119987 0.00792998 0.01894998 0.01826995 0.01008999 0.01894998 0.01726996 -0.007959961 0.01894998 0.01832997 -0.004529953 0.01894998 0.01947999 -0.01668 0.01894998 0.01102995 -0.01892 0.01881998 0.007889986 -0.02024996 0.01843994 0.004999995 -0.02017998 0.01855999 0.004999995 -0.00812 0.01894998 -0.01827996 0.006659984 0.01894998 -0.01885998 0.01576 0.01894998 0.01230996 0.002989947 0.01894998 0.01976996 0.002719998 0.01894998 0.01978999 -0.01141995 0.01894998 0.01641994 -0.01256996 0.01894998 0.01545 -0.01767998 0.01894998 -0.009159982 -0.01892 0.01881998 -0.007889986 -0.01937997 0.01794999 -0.008079946 -0.01830995 0.01794999 -0.01009994 -0.01925998 0.01844996 -0.008029997 -0.01458996 0.01894998 -0.01362997 -0.01709997 0.01881998 -0.01130998 -0.01750999 0.01794999 -0.01159 -0.0151 0.01794999 -0.01457995 -0.01739996 0.01844996 -0.01150995 -0.01431 0.01894998 -0.01397997 -0.01466 0.01881998 -0.01432996 -0.01501995 0.01794999 -0.01467996 -0.01491999 0.01844996 -0.01457995 -0.01034998 0.01894998 -0.01701998 -0.008319973 0.01881998 -0.01872998 -0.01169997 0.01881998 -0.01682996 -0.01198995 0.01794999 -0.01723998 -0.01190996 0.01844996 -0.01712995 -8.2e-4 0.01794999 -0.02098 -0.004759967 0.01794999 -0.02044999 -0.004729986 0.01844996 -0.02031999 -0.005689978 0.01794999 -0.02013999 -0.01073998 0.01794999 -0.01794999 -0.008529961 0.01794999 -0.01918995 -0.008469998 0.01844996 -0.01906996 -2.5e-4 0.01794999 -0.02094995 -8.2e-4 0.01844996 -0.02085 -8.1e-4 0.01881998 -0.02047997 -0.005379974 0.01894998 -0.01919996 -0.004649996 0.01881998 -0.01996999 -0.004529953 0.01894998 -0.01947999 0.005379974 0.01894998 -0.01917999 0.006829977 0.01881998 -0.01932996 0.003069996 0.01881998 -0.02026998 0.003139972 0.01794999 -0.02075999 0.003119945 0.01844996 -0.02063 0.01381999 0.01794999 -0.01580995 0.01059997 0.01794999 -0.01813 0.01052999 0.01844996 -0.01800996 0.01034998 0.01794999 -0.01824998 0.005209982 0.01794999 -0.02024996 0.006989955 0.01794999 -0.01979994 0.006949961 0.01844996 -0.01966995 0.01469999 0.01794999 -0.01488 0.01372998 0.01844996 -0.01570999 0.01348996 0.01881998 -0.01542997 0.01008999 0.01894998 -0.01726996 0.01034998 0.01881998 -0.01769995 0.01036995 0.01894998 -0.01705998 0.01774996 0.01894998 -0.009199976 0.01823997 0.01881998 -0.009349942 0.01615995 0.01881998 -0.01261997 0.01655 0.01794999 -0.01291996 0.01644998 0.01844996 -0.01283997 0.02090996 0.01794999 -0.00198996 0.02023994 0.01794999 -0.005469977 0.02002996 0.01844996 -0.005849957 0.02015995 0.01794999 -0.005889952 0.01807999 0.01794999 -0.01052999 0.01868999 0.01794999 -0.009579956 0.01857 0.01844996 -0.009519994 0.02090996 0.01794999 0 0.02076995 0.01844996 -0.001969993 0.02041 0.01881998 -0.001939952 0.01919996 0.01894998 -0.005609989 0.01967996 0.01881998 -0.00575 0.01949995 0.01894998 -0.004049956 0.01990997 0.01894998 0.001889944 0.02041 0.01881998 0.001939952 0.02090996 0.01794999 0.00198996 0.02023994 0.01794999 0.005469977 0.02076995 0.01844996 0.001969993 0.01876997 0.01894998 0.006669998 0.01967996 0.01881998 0.00575 0.02015995 0.01794999 0.005889952 0.02002996 0.01844996 0.005849957 0.01627999 0.01894998 0.0115 0.01615995 0.01881998 0.01261997 0.01823997 0.01881998 0.009349942 0.01868999 0.01794999 0.009579956 0.01857 0.01844996 0.009519994 0.01059997 0.01794999 0.01813 0.01381999 0.01794999 0.01580995 0.01372998 0.01844996 0.01570999 0.01469999 0.01794999 0.01488 0.01807999 0.01794999 0.01052999 0.01655 0.01794999 0.01291996 0.01644998 0.01844996 0.01283997 0.01034998 0.01794999 0.01824998 0.01052999 0.01844996 0.01800996 0.01034998 0.01881998 0.01769995 0.01315999 0.01894998 0.01505994 0.01348996 0.01881998 0.01542997 0.01258999 0.01894998 0.01546996 0.006659984 0.01894998 0.01885998 0.003069996 0.01881998 0.02026998 0.006829977 0.01881998 0.01932996 0.006989955 0.01794999 0.01979994 0.006949961 0.01844996 0.01966995 -0.004759967 0.01794999 0.02044999 -8.2e-4 0.01794999 0.02098 -8.2e-4 0.01844996 0.02085 -2.5e-4 0.01794999 0.02094995 0.005209982 0.01794999 0.02024996 0.003139972 0.01794999 0.02075999 0.003119945 0.01844996 0.02063 -0.005689978 0.01794999 0.02013999 -0.004729986 0.01844996 0.02031999 -0.004649996 0.01881998 0.01996999 -7.8e-4 0.01894998 0.01997995 -8.1e-4 0.01881998 0.02047997 -0.002709984 0.01894998 0.01972997 -0.00812 0.01894998 0.01827996 -0.01169997 0.01881998 0.01682996 -0.008319973 0.01881998 0.01872998 -0.008529961 0.01794999 0.01918995 -0.008469998 0.01844996 0.01906996 -0.01750999 0.01794999 0.01159 -0.0151 0.01794999 0.01457995 -0.01491999 0.01844996 0.01457995 -0.01501995 0.01794999 0.01467996 -0.01073998 0.01794999 0.01794999 -0.01198995 0.01794999 0.01723998 -0.01190996 0.01844996 0.01712995 -0.01937997 0.01794999 0.008079946 -0.01830995 0.01794999 0.01009994 -0.01925998 0.01844996 0.008029997 -0.01739996 0.01844996 0.01150995 -0.01709997 0.01881998 0.01130998 -0.01431 0.01894998 0.01397997 -0.01466 0.01881998 0.01432996 -0.01629996 0.01894998 0.0115 -0.01014 0.03504997 -0.01576995 -0.005279958 0.03504997 0.01798999 0 0.03504997 0.01874995 0.005279958 0.03504997 0.01798999 0.01014 0.03504997 0.01576995 0.01416999 0.03504997 0.01227998 0.01705998 0.03504997 0.007789969 0.01855999 0.03504997 0.00266999 0.01855999 0.03504997 -0.00266999 -0.01014 0.03504997 0.01576995 -0.01416999 0.03504997 0.01227998 -0.01705998 0.03504997 0.007789969 -0.01855999 0.03504997 0.00266999 -0.01855999 0.03504997 -0.00266999 -0.01705998 0.03504997 -0.007789969 -0.01416999 0.03504997 -0.01227998 -0.005279958 0.03504997 -0.01798999 0 0.03504997 -0.01874995 0.005279958 0.03504997 -0.01798999 0.01014 0.03504997 -0.01576995 0.01416999 0.03504997 -0.01227998 0.01705998 0.03504997 -0.007789969 0.001609981 0.03494995 -0.01717996 -0.003309965 0.03504997 -0.01692998 -0.003309965 0.03494995 -0.01692998 0.001759946 0.03494995 -0.01713997 0.001969993 0.03494995 -0.01708996 0.001609981 0.03504997 -0.01717996 0.004629969 0.03494995 -0.01644998 0.006399989 0.03494995 -0.01601999 0.007199943 0.03494995 -0.01555997 0.007989943 0.03494995 -0.0151 0.006399989 0.03504997 -0.01601999 0.009659945 0.03494995 -0.01413995 0.01066994 0.03494995 -0.01354998 0.01066994 0.03504997 -0.01354998 0.01512998 0.03494995 -0.007909953 0.01104998 0.03494995 -0.01314997 0.01406997 0.03504997 -0.009979963 0.01406997 0.03494995 -0.009979963 0.01695996 0.03494995 -0.002209961 0.01631999 0.03494995 -0.005589962 0.01631999 0.03504997 -0.005589962 0.01652997 0.03494995 -0.004479944 -0.007969975 0.03494995 -0.01529997 -0.007969975 0.03504997 -0.01529997 -0.009269952 0.03494995 -0.01454997 -0.01002997 0.03494995 0.01388996 -0.01088994 0.03494995 0.01314997 -0.01299995 0.03494995 0.01133996 -0.01299995 0.03504997 0.01133996 -0.01378995 0.03494995 0.01010996 -0.01567995 0.03494995 0.007189989 -0.01567995 0.03504997 0.007189989 -0.01626998 0.03494995 0.005199968 -0.01706999 0.03494995 0.002459943 -0.01706999 0.03494995 0.002019941 -0.01706999 0.03494995 9.7e-4 -0.01706999 0.03494995 6.9e-4 -0.01706999 0.03504997 0.002459943 -0.01706999 0.03494995 -0.002209961 -0.01706999 0.03494995 -0.002459943 -0.01706999 0.03504997 -0.002459943 -0.01647996 0.03494995 -0.004479944 -0.01567995 0.03494995 -0.007189989 -0.01567995 0.03504997 -0.007189989 -0.01521998 0.03494995 -0.007909953 -0.01299995 0.03504997 -0.01133996 -0.01299995 0.03494995 -0.01133996 -0.01002997 0.03494995 -0.01388996 -0.01088994 0.03494995 -0.01314997 -0.009269952 0.03504997 -0.01454997 -0.009269952 0.03494995 0.01454997 -0.009269952 0.03504997 0.01454997 0.01718997 0.03494995 9.7e-4 0.01699 0.03494995 0.002019941 0.01638996 0.03494995 0.005199968 0.01631999 0.03494995 0.005589962 0.01631999 0.03504997 0.005589962 0.01104998 0.03494995 0.01314997 0.01406997 0.03494995 0.009979963 0.01406997 0.03504997 0.009979963 0.01394999 0.03494995 0.01010996 0.01066994 0.03494995 0.01354998 0.009659945 0.03494995 0.01413995 0.01066994 0.03504997 0.01354998 0.007199943 0.03494995 0.01555997 0.006399989 0.03494995 0.01601999 0.006399989 0.03504997 0.01601999 0.004629969 0.03494995 0.01644998 0.001969993 0.03494995 0.01708996 0.001759946 0.03494995 0.01713997 0.001609981 0.03494995 0.01717996 0.001609981 0.03504997 0.01717996 -0.003309965 0.03494995 0.01692998 -0.007969975 0.03504997 0.01529997 -0.007969975 0.03494995 0.01529997 -0.003309965 0.03504997 0.01692998 0.01722997 0.03504997 7.5e-4 0.01722997 0.03494995 7.5e-4 0.01722997 0.03494995 -7.5e-4 0.01722997 0.03504997 -7.5e-4 -0.02063995 0.005949974 0.006999969 -0.02213996 0.005949974 0.004869997 -0.02213996 0.005949974 -0.004869997 -0.02263998 0.005949974 -0.003999948 -0.02263998 0.005949974 0 -0.02263998 0.005949974 0.003999948 -0.02249997 0.005949974 -0.004499971 -0.02249997 0.005949974 0.004499971 -0.01838999 0.005949974 -0.01014 -0.01510995 0.005949974 -0.01458996 -0.01510995 0.005949974 0.01458996 -0.01077997 0.005949974 -0.01801997 -0.01077997 0.005949974 0.01801997 -0.005709946 0.005949974 -0.02020996 -0.005709946 0.005949974 0.02020996 -2.5e-4 0.005949974 -0.02099996 -2.5e-4 0.005949974 0.02099996 0 0.005949974 -0.02096998 0 0.005949974 0.02096998 0.005239963 0.005949974 -0.02033996 0.005239963 0.005949974 0.02033996 0.01036 0.005949974 -0.01826995 0.01036 0.005949974 0.01826995 0.01475995 0.005949974 -0.01493996 0.01475995 0.005949974 0.01493996 0.01814997 0.005949974 -0.01056998 0.01814997 0.005949974 0.01056998 0.02026998 0.005949974 -0.005479991 0.02099996 0.005949974 0 0.02026998 0.005949974 0.005479991 -0.02499997 -0.03504997 -0.023 -0.02499997 -0.03504997 0.023 -0.02472996 -0.03504997 -0.02399998 -0.02472996 -0.03504997 0.02399998 -0.02399998 -0.03504997 -0.02472996 -0.02399998 -0.03504997 0.02472996 -0.02363997 0.003949999 -0.02164 -0.02363997 0.003949999 0.02164 -0.02363997 0.00544995 -0.02164 -0.02363997 0.00544995 0.02164 -0.02357 0.005699992 -0.02164 -0.02357 0.005699992 0.02164 -0.02338999 0.005879998 -0.02164 -0.02338999 0.005879998 0.02164 -0.02336996 0.003959953 0.02263998 -0.02336996 0.00544995 -0.02263998 -0.02336996 0.00544995 0.02263998 -0.02336996 0.003959953 -0.02263998 -0.02331 0.005699992 -0.02260994 -0.02331 0.005699992 0.02260994 -0.02314996 0.005879998 -0.02250999 -0.02314996 0.005879998 0.02250999 -0.02313995 0.005949974 -0.02164 -0.02313995 0.005949974 0 -0.02313995 0.005949974 0.02164 -0.023 -0.03504997 -0.02499997 -0.023 -0.03504997 0.02499997 -0.02293998 0.005949974 -0.02238994 -0.02293998 0.005949974 0.02238994 0 -0.03504997 0 -0.02263998 0.003959953 0.02336996 -0.02263998 0.003959953 -0.02336996 -0.02263998 0.00544995 -0.02336996 -0.02263998 0.00544995 0.02336996 -0.02260994 0.005699992 -0.02331 -0.02260994 0.005699992 0.02331 -0.02250999 0.005879998 -0.02314996 -0.02250999 0.005879998 0.02314996 0 0.005949974 -0.02313995 -0.02164 0.005949974 -0.02313995 -0.02238994 0.005949974 -0.02293998 -0.02238994 0.005949974 0.02293998 -0.02164 0.003949999 -0.02363997 -0.02164 0.003949999 0.02363997 -0.02164 0.00544995 -0.02363997 -0.02164 0.00544995 0.02363997 -0.02164 0.005699992 -0.02357 -0.02164 0.005699992 0.02357 -0.02164 0.005879998 -0.02338999 -0.02164 0.005879998 0.02338999 -0.02164 0.005949974 0.02313995 -0.005709946 0.005949974 -0.02020996 -0.01077997 0.005949974 -0.01801997 -0.01510995 0.005949974 -0.01458996 -0.01838999 0.005949974 -0.01014 -0.02213996 0.005949974 -0.004869997 0 0.005949974 0.02313995 0.02164 0.003949999 -0.02363997 0.02164 0.003949999 0.02363997 0.02164 0.00544995 -0.02363997 0.02164 0.00544995 0.02363997 0.02164 0.005699992 -0.02357 0.02164 0.005699992 0.02357 0.02164 0.005879998 -0.02338999 0.02164 0.005879998 0.02338999 0.02164 0.005949974 -0.02313995 0.02164 0.005949974 0.02313995 0.02238994 0.005949974 -0.02293998 0.02238994 0.005949974 0.02293998 0.02250999 0.005879998 -0.02314996 0.02250999 0.005879998 0.02314996 0.02260994 0.005699992 -0.02331 0.02260994 0.005699992 0.02331 0.02263998 0.003959953 -0.02336996 0.02263998 0.003959953 0.02336996 0.02263998 0.00544995 -0.02336996 0.02263998 0.00544995 0.02336996 0.02293998 0.005949974 -0.02238994 0.02293998 0.005949974 0.02238994 0.023 -0.03504997 -0.02499997 0.023 -0.03504997 0.02499997 0.02313995 0.005949974 -0.02164 0.02313995 0.005949974 0 0.02313995 0.005949974 0.02164 0.02314996 0.005879998 -0.02250999 0.02314996 0.005879998 0.02250999 0.02331 0.005699992 -0.02260994 0.02331 0.005699992 0.02260994 0.02336996 0.003959953 -0.02263998 0.02336996 0.003959953 0.02263998 0.02336996 0.00544995 -0.02263998 0.02336996 0.00544995 0.02263998 0.02338999 0.005879998 -0.02164 0.02338999 0.005879998 0.02164 0.02357 0.005699992 -0.02164 0.02357 0.005699992 0.02164 0.02363997 0.003949999 -0.02164 0.02363997 0.003949999 0.02164 0.02363997 0.00544995 -0.02164 0.02363997 0.00544995 0.02164 0.02399998 -0.03504997 -0.02472996 0.02399998 -0.03504997 0.02472996 0.02472996 -0.03504997 -0.02399998 0.02472996 -0.03504997 0.02399998 0.02499997 -0.03504997 -0.023 0.02499997 -0.03504997 0.023 0 0.03504997 0 -0.02213996 0.005949974 0.004869997 -0.02063995 0.005949974 0.006999969 -0.01979994 0.005949974 0.006999969 -0.01838999 0.005949974 0.01014 -0.02113997 0.005949974 0.006869971 -0.02149999 0.005949974 0.006499946 -0.02164 0.005949974 0.005999982 -0.02164 0.005949974 0.004999995 -0.02263998 0.005949974 -0.003999948 -0.02263998 0.005949974 0.003999948 -0.02249997 0.005949974 -0.004499971 -0.02249997 0.005949974 0.004499971 -0.01838999 0.005949974 -0.01014 -0.01510995 0.005949974 -0.01458996 -0.01510995 0.005949974 0.01458996 -0.01077997 0.005949974 -0.01801997 -0.01077997 0.005949974 0.01801997 -0.005709946 0.005949974 -0.02020996 -0.005709946 0.005949974 0.02020996 -2.5e-4 0.005949974 -0.02099996 -2.5e-4 0.005949974 0.02099996 0 0.005949974 -0.02096998 0 0.005949974 0.02096998 0.005239963 0.005949974 -0.02033996 0.005239963 0.005949974 0.02033996 0.01036 0.005949974 -0.01826995 0.01036 0.005949974 0.01826995 0.01475995 0.005949974 -0.01493996 0.01475995 0.005949974 0.01493996 0.01814997 0.005949974 -0.01056998 0.01814997 0.005949974 0.01056998 0.02026998 0.005949974 -0.005479991 0.02099996 0.005949974 0 0.02026998 0.005949974 0.005479991 -0.005709946 0.005949974 -0.02020996 -0.01077997 0.005949974 -0.01801997 -0.01510995 0.005949974 -0.01458996 -0.01838999 0.005949974 -0.01014 -0.01979994 0.005949974 0.006999969 -0.01838999 0.005949974 0.01014 -0.02113997 0.005949974 0.006869971 -0.02149999 0.005949974 0.006499946 -0.02164 0.005949974 0.005999982 -0.02164 0.005949974 0.004999995 -0.02263998 0.005949974 -0.003999948 -0.02263998 0.005949974 0.003999948 -0.02249997 0.005949974 -0.004499971 -0.02249997 0.005949974 0.004499971 -0.01838999 0.005949974 -0.01014 -0.01510995 0.005949974 -0.01458996 -0.01510995 0.005949974 0.01458996 -0.01077997 0.005949974 -0.01801997 -0.01077997 0.005949974 0.01801997 -0.005709946 0.005949974 -0.02020996 -0.005709946 0.005949974 0.02020996 -2.5e-4 0.005949974 -0.02099996 -2.5e-4 0.005949974 0.02099996 0 0.005949974 -0.02096998 0 0.005949974 0.02096998 0.005239963 0.005949974 -0.02033996 0.005239963 0.005949974 0.02033996 0.01036 0.005949974 -0.01826995 0.01036 0.005949974 0.01826995 0.01475995 0.005949974 -0.01493996 0.01475995 0.005949974 0.01493996 0.01814997 0.005949974 -0.01056998 0.01814997 0.005949974 0.01056998 0.02026998 0.005949974 -0.005479991 0.02099996 0.005949974 0 0.02026998 0.005949974 0.005479991 -0.005709946 0.005949974 -0.02020996 -0.01077997 0.005949974 -0.01801997 -0.01510995 0.005949974 -0.01458996 -0.01838999 0.005949974 -0.01014 -0.02063995 0.005949974 0.006999969 -0.02213996 0.005949974 0.004869997 -0.02213996 0.005949974 -0.004869997 -0.01979994 0.005949974 0.006999969 -0.01838999 0.005949974 0.01014 -0.02113997 0.005949974 0.006869971 -0.02149999 0.005949974 0.006499946 -0.02164 0.005949974 0.005999982 -0.02164 0.005949974 0.004999995 -0.02263998 0.005949974 -0.003999948 -0.02263998 0.005949974 0.003999948 -0.02249997 0.005949974 -0.004499971 -0.02249997 0.005949974 0.004499971 -0.01838999 0.005949974 -0.01014 -0.01510995 0.005949974 -0.01458996 -0.01510995 0.005949974 0.01458996 -0.01077997 0.005949974 -0.01801997 -0.01077997 0.005949974 0.01801997 -0.005709946 0.005949974 -0.02020996 -0.005709946 0.005949974 0.02020996 -2.5e-4 0.005949974 -0.02099996 -2.5e-4 0.005949974 0.02099996 0 0.005949974 -0.02096998 0 0.005949974 0.02096998 0.005239963 0.005949974 -0.02033996 0.005239963 0.005949974 0.02033996 0.01036 0.005949974 -0.01826995 0.01036 0.005949974 0.01826995 0.01475995 0.005949974 -0.01493996 0.01475995 0.005949974 0.01493996 0.01814997 0.005949974 -0.01056998 0.01814997 0.005949974 0.01056998 0.02026998 0.005949974 -0.005479991 0.02099996 0.005949974 0 0.02026998 0.005949974 0.005479991 -0.005709946 0.005949974 -0.02020996 -0.01077997 0.005949974 -0.01801997 -0.01510995 0.005949974 -0.01458996 -0.01838999 0.005949974 -0.01014 -0.00945729 0.003627836 -0.001710772 0 -0.01554995 0.02431994 0 0.005949974 0 + + + + + + + + + + + +0 -1 0 0 -1 0 -0.9492978 0 -0.3143782 -0.9492978 0 0.3143782 -0.7785766 0.001171708 0.6275485 -0.7808654 0.001171231 0.6246982 -0.6209343 -0.001221954 0.7838616 -0.6453004 -0.01542252 0.7637733 -0.3964945 -0.0151537 0.9179121 -0.4893132 0.006718158 0.8720822 -0.4938785 0.006718337 0.8695049 -0.1431924 -0.008457064 0.9896588 -0.316222 0.006060898 0.9486659 -0.3172233 0.0060606 0.9483315 0.2392156 0.007879972 0.9709345 0.119358 -0.01385879 0.9927546 0.0559594 0.00282979 0.9984291 0.1191433 0.00413686 0.9928685 0.05255794 0.004160761 0.9986092 -0.1333157 -0.004680752 0.9910625 0.2450903 0.007883667 0.9694681 0.3747907 -0.01294112 0.9270192 0.4188861 0.001862525 0.9080369 0.4327281 0.001863181 0.9015226 0.6034716 -0.002766609 0.7973797 0.5845207 -0.01302987 0.8112742 0.7900453 -0.01468151 0.6128727 0.7272006 0.007067918 0.6863886 0.7263449 0.007068157 0.6872941 0.9823358 0.002611696 0.1871086 0.9289886 -0.004128932 0.3700852 0.9230861 -0.009820222 0.3844679 0.8414472 0.006709396 0.5402976 0.8421885 0.006709873 0.5391413 0.9819628 0.002612411 0.1890563 0.9911401 -0.01446169 0.1320315 0.9999719 0.007499694 0 0.9999719 0.007499694 0 0.9911401 -0.01446169 -0.1320315 0.9819628 0.002612411 -0.1890563 0.9823358 0.002611696 -0.1871086 0.9231205 -0.004674613 -0.3844823 0.9289375 -0.01127177 -0.3700649 0.7900453 -0.01468151 -0.6128727 0.8421885 0.006709873 -0.5391413 0.8414472 0.006709396 -0.5402976 0.4327281 0.001863181 -0.9015226 0.5845689 -0.002225697 -0.8113411 0.6034404 -0.0105375 -0.7973385 0.7263449 0.007068157 -0.6872941 0.7272006 0.007067918 -0.6863886 0.4188861 0.001862525 -0.9080369 0.3747907 -0.01294112 -0.9270192 0.2450903 0.007883667 -0.9694681 0.2392156 0.007879972 -0.9709345 0.119358 -0.01385879 -0.9927546 0.0559594 0.00282979 -0.9984291 0.1191433 0.00413686 -0.9928685 0.05255794 0.004160761 -0.9986092 -0.1431956 -0.005152344 -0.989681 -0.1333114 -0.009266734 -0.9910309 -0.3964945 -0.0151537 -0.9179121 -0.3172233 0.0060606 -0.9483315 -0.316222 0.006060898 -0.9486659 -0.7808654 0.001171231 -0.6246982 -0.6453768 -8.88654e-4 -0.7638639 -0.6208926 -0.01165908 -0.783809 -0.4938785 0.006718337 -0.8695049 -0.4893132 0.006718158 -0.8720822 -0.7785766 0.001171708 -0.6275485 -0.8049004 -0.01266139 -0.5932749 -0.881016 0.007450222 -0.4730277 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.9471516 0.1680965 0.2732169 -0.407418 0.1514139 -0.9006023 -0.9422059 0.2770094 -0.1884511 -0.9113164 0.1482697 -0.3840813 -0.9315509 0.1626105 -0.3252239 -0.7991091 -0.3146805 -0.5122509 -0.9081746 0.2506373 -0.3352608 -0.9111543 0.1456485 -0.3854666 -0.928664 0.2243673 -0.2953684 -0.925579 0.2859641 -0.2480482 -0.9177774 0.2868903 0.2745518 -0.9178981 0.2856691 0.2754201 -0.9143468 0.1813663 0.3620446 -0.9384292 0.1466302 0.31281 -0.9311535 0.1683419 0.3234411 -0.901751 0.1467134 0.4065961 -0.9103941 0.1680585 0.3780726 -0.912325 0.3225979 0.2521777 -0.9188216 0.2869244 0.2710005 -0.9848498 0.1048805 0.138097 -0.9578264 0.2873474 0 -0.9559739 0.2861407 -0.06509518 -0.9987523 -0.04993659 0 -0.9210147 0.2770513 -0.2738146 -0.4861897 0.1523008 -0.8604789 -0.4091901 0.1777053 -0.8949773 -0.3149025 0.1457877 -0.9378605 -0.1278769 0.1498839 -0.9803991 -0.309273 0.1512408 -0.9388697 -0.141013 0.1688628 -0.9755002 -0.1303948 0.1630746 -0.977959 -0.4837509 0.1474936 -0.8626881 -0.636475 0.163087 -0.7538581 -0.645197 0.1696269 -0.744948 -0.7708169 0.1599442 -0.6166515 -0.6459589 0.159875 -0.746443 -0.7711567 0.1450923 -0.6198915 -0.8274903 0.1763324 -0.533073 -0.8709936 0.1562899 -0.4657721 -0.9149418 0.1555567 -0.3724025 -0.7441748 0.5367867 -0.3975726 -0.9384292 0.1466302 -0.3128098 -0.9364062 0.1603595 0.3121352 -0.8722791 0.1474033 0.4662632 -0.8271023 0.1767897 0.5335236 -0.7664864 0.1686882 0.6197121 -0.8297607 0.1690638 0.5318973 -0.7716946 0.1450895 0.6192225 -0.6450954 0.1696101 0.7450398 -0.6363618 0.1663306 0.7532449 -0.64563 0.1662972 0.7453235 -0.6361207 0.1630551 0.754164 -0.4856274 0.1477051 0.8615968 -0.4099487 0.177209 0.8947284 -0.2937462 0.1736751 0.9399735 -0.4077602 0.1746891 0.8962228 -0.3145152 0.1452308 0.9380769 -0.1418845 0.1683772 0.9754577 -0.1341822 0.1666406 0.976845 -0.1389042 0.1666364 0.9761855 -0.1267469 0.1627997 0.9784843 0.1395421 0.1371724 0.980669 0.05338537 0.1733645 0.9834097 0.07274723 0.1735997 0.9821257 0.1416881 0.1761806 0.9741073 0.2381073 0.1455035 0.9602779 0.4082419 0.1680009 0.8972816 0.4154286 0.1666471 0.8942303 0.4107152 0.1666655 0.8964015 0.4143497 0.165222 0.894995 0.6486326 0.1363442 0.7487897 0.575868 0.1693211 0.7998164 0.575499 0.1693159 0.8000832 0.6442187 0.1772168 0.7440273 0.7189208 0.1454344 0.6797072 0.8300612 0.16697 0.5320899 0.8296917 0.1670521 0.5326398 0.8285282 0.1670665 0.5344434 0.8312138 0.1651425 0.5308593 0.9521918 0.1337416 0.2746708 0.9171259 0.1644181 0.3631072 0.914055 0.1643574 0.3707966 0.9438654 0.1778166 0.2783871 0.9717582 0.1459009 0.1854698 0.9860588 0.1663975 0 0.9860587 0.1663975 0 0.9860587 0.1663975 0 0.9860587 0.1663975 0 0.9500489 0.1327823 -0.2824464 0.9697747 0.1601643 -0.1840775 0.9693279 0.1601721 -0.1864089 0.9447124 0.1775989 -0.2756393 0.830715 0.1654286 -0.5315507 0.8288937 0.166745 -0.533977 0.7189707 0.1454441 -0.6796524 0.6466634 0.1530798 -0.747257 0.717962 0.1537514 -0.6788895 0.6443232 0.1772074 -0.743939 0.5763537 0.1462174 -0.8040131 0.4070715 0.1568021 -0.8998366 0.5925795 0.1567866 -0.7901059 0.4147536 0.1656929 -0.8947209 0.4098841 0.1681987 -0.8964955 0.2399455 0.1457665 -0.9597803 0.1279237 0.1474865 -0.9807565 0.2369926 0.1489789 -0.9600207 0.1408129 0.1768286 -0.9741167 0.05614864 0.1468989 -0.9875566 0.05065917 0.1469421 -0.987847 -0.1424711 -3.79589e-4 -0.9897989 -0.129338 0 -0.9916005 -0.4158082 0 -0.9094523 -0.4154945 -2.07829e-4 -0.9095956 -0.4121701 0 -0.911107 -0.6546844 0 -0.7559022 -0.6546447 -3.01789e-5 -0.7559368 -0.6543759 0 -0.7561693 -0.840663 0 -0.5415588 -0.8408741 2.12565e-4 -0.5412307 -0.8418785 0 -0.5396671 -0.9599732 0 -0.280092 -0.9596633 -5.69179e-4 -0.2811512 -0.9585365 0 -0.2849697 -1 0 0 -1 0 0 -1 0 0 -0.9591508 0 0.2828954 -0.9596631 -8.33003e-4 0.2811512 -0.9608235 0 0.2771607 -0.8403387 0 0.5420618 -0.840874 -4.25545e-4 0.5412307 -0.8418794 0 0.5396656 -0.6545795 0 0.7559933 -0.6546447 -3.46783e-5 0.7559368 -0.6547469 0 0.7558482 -0.4165412 0 0.9091168 -0.4154945 4.29833e-4 0.9095956 -0.4141279 0 0.9102187 -0.1439396 0 0.9895865 -0.142471 5.09058e-4 0.9897989 -0.1408738 0 0.9900277 0.1408738 0 0.9900277 0.142471 5.09058e-4 0.9897989 0.1439396 0 0.9895865 0.4141279 0 0.9102187 0.4154945 4.29833e-4 0.9095956 0.4165412 0 0.9091168 0.6547469 0 0.7558482 0.6546447 -3.46783e-5 0.7559368 0.6545795 0 0.7559933 0.8418794 0 0.5396656 0.840874 -4.25545e-4 0.5412307 0.8403387 0 0.5420618 0.9608235 0 0.2771607 0.9596631 -8.33003e-4 0.2811512 0.9591508 0 0.2828954 1 0 0 1 0 0 1 0 0 0.9585365 0 -0.2849697 0.9596633 -5.69179e-4 -0.2811512 0.9599732 0 -0.280092 0.8418785 0 -0.5396671 0.8408741 2.12565e-4 -0.5412307 0.840663 0 -0.5415588 0.6543759 0 -0.7561693 0.6546447 -3.01789e-5 -0.7559368 0.6546844 0 -0.7559022 0.4121701 0 -0.911107 0.4154945 -2.07829e-4 -0.9095956 0.4158082 0 -0.9094523 0.129338 0 -0.9916005 0.1424711 -3.79589e-4 -0.9897989 0.1430675 0 -0.9897129 -0.1430675 0 -0.9897129 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.9838701 0.1788842 -0.007730364 0.9677938 0.2516258 -0.008649408 0.7070808 0.7070799 0.006879746 0.8947982 0.4464178 0.006871819 0.8719238 0.4895934 0.002814829 0.377206 0.9261251 -0.008792817 0.2516237 0.9677851 0 0.1293374 0.9916006 -0.9629649 0 0.269627 -0.9629649 0 0.269627 -0.251012 0.07028329 0.965429 -0.1845505 0.1845505 0.9653404 -0.07028359 0.2510112 0.9654293 -0.1942211 0.6936423 0.6936414 -0.1935422 0.6935194 0.6939541 -0.5112335 0.5112336 0.690855 -0.5112314 0.5112344 0.690856 -0.6932809 0.1941184 0.6940315 -0.7049736 0.1803423 0.6859219 -0.2607492 0.9343423 0.2429284 -0.243086 0.9349478 0.2584215 -0.682882 0.6828859 0.2594976 -0.6944488 0.6756823 0.2473751 -0.9403539 0.2405559 0.2405565 -0.9297617 0.2603295 0.2603303 -0.2516335 0.9678226 0 -0.2516335 0.9678226 0 -0.7167247 0.6973562 0 -0.7167247 0.6973562 0 -0.962965 0.2696263 0 -0.962965 0.2696263 0 -0.7167251 0 -0.6973558 -0.9629649 0 -0.269627 -0.9629649 0 -0.269627 -0.07028359 0.2510112 -0.9654293 -0.1845506 0.1845506 -0.9653404 -0.2440263 0.938564 -0.2440261 -0.2595868 0.9301772 -0.2595866 -0.6923445 0.673635 -0.2586021 -0.6852509 0.685255 -0.2466917 -0.9343009 0.2616005 -0.2421712 -0.9350127 0.2391895 -0.2618005 -0.1936007 0.6937291 -0.6937282 -0.1941202 0.693282 -0.6940299 -0.5112318 0.5112348 -0.6908552 -0.5112326 0.5112326 -0.6908563 -0.6994224 0.1789222 -0.6919503 -0.7027144 0.1967598 -0.6837237 -0.251012 0.07028329 -0.965429 0 0.1543763 -0.9880121 -0.009795784 0.2516214 -0.9677761 -0.007334709 0.722306 -0.6915347 0.00679636 0.4472005 -0.8944079 0.006780803 0.5067117 -0.8620889 -0.009076535 0.9677828 -0.2516229 0 0.9892032 -0.1465499 -0.2263051 0.7072249 0.6697902 0.3015977 0.696307 0.6513029 0.7167264 0.6973544 0 0.5183387 0.69911 -0.4925142 0.03862148 0.6995103 -0.7135781 -0.1644762 0.9669772 0.1946862 -0.1248043 0.9671578 0.2214269 0.01370066 0.9675313 0.2523798 0.06004744 0.9683741 0.2421693 0.1849305 0.9670732 0.1748434 0.1059339 0.9677575 -0.2285243 -0.1261059 0.966584 -0.2231875 -0.199501 0.9668129 -0.1596003 -0.6712515 0.704275 -0.2311238 -0.4654791 0.8727707 -0.1469718 -0.4844728 0.8612704 -0.1532949 -0.8913083 0.3450198 -0.2941612 -0.915989 0.251125 -0.3128905 -0.944593 0.09943693 -0.3128201 -0.9346077 0.1752427 0.3095133 -0.9163941 0.251105 0.3117182 -0.8494461 0.4497035 0.2760577 -0.6587777 0.7186641 0.2225626 -0.11454 0.9926847 0.03817999 -0.2079164 0.9745261 0.08408081 -0.2403051 0.9673867 0.08010166 -0.2239108 0.9672326 0.119688 -0.2239329 0.9672339 -0.1196353 -0.2369856 0.9674997 -0.08821576 -0.168695 0.984063 -0.05623167 -0.220901 0.9681158 -0.1181289 -0.195109 0.9681603 -0.1568376 -0.1642051 0.9670629 -0.194489 -0.1243403 0.9671458 -0.2217399 -0.03328311 0.9677709 -0.249623 0.01294058 0.9675522 -0.2523397 0.01371669 0.9672559 -0.2534325 0.01418453 0.9682756 -0.2494817 0.05979275 0.9683793 -0.2422114 0.1485582 0.966945 -0.2072386 0.1849181 0.9670735 -0.1748546 0.1827625 0.9676989 -0.173657 0.181624 0.9682638 -0.1716915 0.2103747 0.9683087 -0.1346127 0.2516335 0.9678226 0 0.2516335 0.9678226 0 0.2516335 0.9678227 0 0.2469634 0.9678903 -0.04687726 0.2482241 0.9675434 0.04737603 0.2343087 0.9675045 0.09504997 0.2367252 0.9670455 0.09372389 0.21423 0.9671535 0.1368191 0.1064419 0.9675605 0.2291214 0.1058055 0.9677801 0.2284879 0.1058276 0.9677543 0.2285876 0.1467888 0.9679301 0.2038734 -0.0766099 0.966454 0.245148 -0.08143335 0.9670985 0.2410164 -0.07958346 0.9681548 0.2373665 -0.03413015 0.9680389 0.2484672 -0.1947117 0.9681448 0.1574264 -0.2211804 0.9681038 0.1177042 -0.6276769 0.7031698 0.3340269 -0.6718416 0.7042246 0.2295574 -0.8316648 0.4851421 0.270131 -0.224141 0.7071188 -0.6706294 -0.08158397 0.9665949 -0.242978 -0.08118349 0.9673035 -0.240277 -0.230294 0.6945442 -0.6815959 -0.09658795 0.6949279 -0.7125629 -0.1300739 0.2494957 -0.9596003 0.05087167 0.2513077 -0.9665695 0.3019366 0.6962896 -0.6511644 0.06135189 0.9674767 -0.2454073 0.1061488 0.9675673 -0.2292293 0.3024179 0.6942894 -0.653074 0.4201316 0.6941274 -0.584531 0.5638182 0.2583763 -0.7844429 0.7015674 0.2590524 -0.6638488 0.657499 0.7065963 -0.2615662 0.6635753 0.6994388 -0.2654304 0.7016292 0.6998641 -0.133816 0.5189352 0.6991608 0.4918134 0.2101477 0.9683169 0.1349092 0.1812267 0.9682484 0.1721977 0.5147917 0.7040795 0.4891439 0.4141255 0.7046437 0.5761747 0.562515 0.2665852 0.7826297 0.4170309 0.2669032 0.8688198 0.03983807 0.6995611 0.7134614 0.01843094 0.9683725 0.2488275 0.01364505 0.9676027 0.2521088 0.03827118 0.7060714 0.7071057 -0.09523808 0.7051784 0.7026044 -0.1298174 0.2567928 0.9577082 -0.305629 0.2567279 0.916887 -0.4603919 0.7019324 0.5434429 -0.1641054 0.967066 0.194558 -0.164548 0.966937 0.1948249 -0.463243 0.6961148 0.5484799 -0.5580259 0.6967077 0.4507831 -0.8506854 0.2602313 -0.4567428 -0.2229626 0.9675791 -0.1186526 -0.6337479 0.6961472 -0.3372576 -0.6271286 0.7031058 -0.3351895 -0.8501825 0.2659004 -0.454408 -0.8554773 0.2506282 -0.4531491 -0.7517282 0.2706233 -0.6013882 -0.1978173 0.9671215 -0.159826 -0.5579887 0.6967101 -0.4508255 -0.5582559 0.6964031 -0.4509689 -0.7490752 0.2696682 -0.6051161 -0.7513393 0.2621917 -0.6055946 -0.1644515 0.9669765 -0.1947106 -0.4595423 0.7019816 -0.5440982 -0.464033 0.6961706 -0.5477408 -0.6238481 0.261821 -0.7363854 -0.621176 0.2712791 -0.7352197 -0.1242595 0.9673138 -0.221051 -0.3465486 0.7069951 -0.6164916 -0.3499536 0.7017597 -0.6205367 -0.4731478 0.2687683 -0.8389843 -0.4767771 0.2609524 -0.839397 -0.1288474 0.2567702 -0.9578452 -0.305629 0.2567279 -0.9168869 -0.3062461 0.2581284 -0.9162877 -0.3065935 0.2567667 -0.916554 -0.4726419 0.2588881 -0.8423696 0.05413478 0.2532923 -0.965874 0.05391412 0.2545722 -0.9655498 0.03948223 0.7060217 -0.7070888 -0.09333491 0.7052802 -0.7027577 -0.03303414 0.9680098 -0.2487279 -0.07829689 0.9681807 -0.2376884 0.06135183 0.9674766 -0.2454078 0.1740778 0.696309 -0.6963121 0.1739403 0.6986982 -0.6939493 0.2341818 0.2688215 -0.9342879 0.2314112 0.2534631 -0.9392579 0.5634199 0.2665578 -0.7819878 0.4170309 0.2669032 -0.8688198 0.4046592 0.2732187 -0.8726983 0.4044461 0.2603067 -0.8767347 0.2365246 0.2621741 -0.9355859 0.7046238 0.2473371 -0.6650787 0.7013934 0.2572429 -0.6647355 0.5154538 0.7040323 -0.488514 0.415661 0.7047259 -0.5749672 0.1455301 0.9686573 -0.2013059 0.15098 0.9678227 -0.2013067 0.2147524 0.9670686 -0.1366009 0.5968894 0.7068039 -0.3796725 0.6017773 0.7001448 -0.3842673 0.8154708 0.2526968 -0.5207222 0.8161497 0.2468252 -0.5224721 0.9629638 0.2696306 0 0.9449788 0.2718722 -0.1819358 0.9482918 0.2608299 -0.18086 0.9482879 0.261008 -0.1806234 0.8967889 0.2617092 -0.3567605 0.8974719 0.258296 -0.3575298 0.8130294 0.2577725 -0.5220504 0.9629638 0.2696306 0 0.9629638 0.2696306 0 0.7167264 0.6973544 0 0.70467 0.6965711 -0.1350152 0.2486808 0.9674128 -0.04764741 0.2481271 0.9675516 -0.04771661 0.9482879 0.261008 0.1806234 0.2469177 0.9678809 0.04730957 0.7014893 0.6998912 0.1344058 0.7047534 0.6966033 0.1344119 0.9482918 0.2608299 0.18086 0.9449788 0.2718721 0.1819358 0.2322279 0.9682156 0.09289127 0.6569463 0.7066604 0.2627788 0.6640112 0.699507 0.2641569 0.8976452 0.2582861 0.3571012 0.8966205 0.2616998 0.3571906 0.2123748 0.9678058 0.1350885 0.6024934 0.7000937 0.3832371 0.59627 0.7067469 0.3807505 0.8154708 0.2526969 0.5207222 0.8130294 0.2577725 0.5220504 0.5647161 0.2584066 0.7837867 0.7015674 0.2590524 0.6638488 0.7013934 0.2572429 0.6647355 0.7046238 0.2473371 0.6650787 0.8161497 0.2468252 0.5224721 0.4044461 0.2603067 0.8767347 0.4046592 0.2732187 0.8726983 0.3027438 0.6943063 0.6529051 0.4217932 0.6940296 0.5834496 0.1488554 0.9671839 0.2059057 0.1488695 0.9669557 0.2069647 0.06135171 0.9674767 0.2454074 0.1735082 0.6987219 0.6940336 0.1745008 0.6963297 0.6961856 0.2341818 0.2688215 0.9342879 0.2365246 0.2621741 0.9355859 -0.1291 0.2495277 0.9597235 0.05087167 0.2513077 0.9665695 0.05391412 0.2545722 0.9655498 0.05413478 0.2532923 0.965874 0.2314112 0.2534631 0.9392579 -0.3065935 0.2567667 0.916554 -0.3062461 0.2581284 0.9162877 -0.2280214 0.6946619 0.6822397 -0.09468263 0.6948394 0.7129049 -0.03354847 0.9669889 0.2526004 -0.03234249 0.9677872 0.2496837 -0.1255912 0.9665973 0.22342 -0.3491178 0.7017115 0.6210619 -0.3474251 0.7069473 0.616053 -0.4731478 0.2687683 0.8389843 -0.4726419 0.2588881 0.8423696 -0.8506854 0.2602313 0.4567428 -0.7513393 0.2621915 0.6055946 -0.7490752 0.2696682 0.6051161 -0.7517282 0.2706233 0.6013882 -0.6221522 0.2713071 0.7343835 -0.6228598 0.2618451 0.7372128 -0.4767771 0.2609524 0.839397 -0.8554773 0.2506282 0.4531491 -0.8501825 0.2659004 0.454408 -0.6330834 0.6962109 0.3383722 -0.5582225 0.6964006 0.4510145 -0.1946848 0.9681715 0.1572951 -0.1992351 0.9668231 0.15987 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.2576645 0 -0.9662344 -0.05074721 0 -0.9987115 -0.05074721 0 -0.9987115 -0.3301701 0 -0.9439214 -0.3301701 0 -0.9439214 0.2314149 -0.04166501 -0.9719626 0.2337992 -0.0328713 -0.9717291 -0.2353472 -0.01319801 0.9718218 0.2360719 0 -0.9717356 0.498471 0 -0.8669065 0.5025548 0.05025458 -0.8630836 0.4977039 -0.0518344 -0.8657968 0.5000953 0.04980254 -0.8645372 0.5044022 0 -0.8634689 0.7249996 0 -0.6887493 0.7241208 -0.006897449 -0.6896386 0.8897777 0 -0.4563943 0.8898923 -0.008304476 -0.4560952 0.8900858 0 -0.4557931 0.7240293 0 -0.6897691 -0.9833266 0 0.1818479 -0.9818185 -0.044227 0.1845983 0.9825241 -0.002599418 -0.1861173 0.9825702 0 -0.1858918 0.6556872 0 0.7550326 -0.6556872 0 0.7550326 -0.6515577 -0.04579263 0.7572157 -0.6516571 -0.04426085 0.7572213 -0.6510875 0 0.7590027 -0.8414006 0 0.540412 -0.8395078 -0.03620713 0.54214 -0.8394931 0 0.5433704 -0.9587494 0 0.2842525 -0.9582376 0.04984301 0.2815961 -0.9599216 0 0.2802686 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.9598937 0 -0.2803642 -0.9588532 0.03467482 -0.281777 -0.9590831 0 -0.2831244 -0.8426965 0 -0.5383889 0.8393291 -0.04166615 0.5420246 0.8395044 0 0.5433529 0.6522963 0 0.757964 0.6490944 0.0781871 0.7566791 0.6515577 0.04579263 0.7572157 0.8899229 0 0.4561109 0.9838697 0 0.1788867 0.9821668 0.01870387 0.187079 0.9826549 -0.003704786 0.1854068 0.9822553 -0.03267395 0.1846804 0.9842713 0 0.1766641 0.8899229 0 0.4561109 0.7249996 0 0.6887493 0.7241208 -0.006897449 0.6896386 0.7232667 0.02902907 0.6899583 0.7348049 0 0.6782786 0.5044022 0 0.8634689 0.4990119 0.0604375 0.864485 0.5005733 0.02391499 0.8653637 0.498471 0 0.8669065 0.2360719 0 0.9717356 0.2353472 0.01319825 0.9718218 0.2337992 -0.03287124 0.9717291 0.2314148 -0.04166501 0.9719625 0.2576645 0 0.9662344 -0.05074721 0 0.9987115 -0.05074721 0 0.9987115 -0.3301701 0 0.9439214 0.3301701 0 -0.9439214 0 -1 0 0 -1 0 0 -1 0 0 0.03485059 -0.9993925 0.9993925 0.03485059 0 1 0 0 0 0 -1 -0.260666 0 0.9654291 -0.9654291 0 -0.260666 -0.9654291 0 -0.260666 -0.260666 0 -0.9654291 -0.9645484 0.04270619 -0.2604277 -0.9646556 0.04270696 -0.2600302 0.9654291 0 -0.260666 0.2604277 0.04270619 -0.9645484 0.7071068 0 0.7071068 0.2689354 0.9604846 -0.07171601 0.2758985 0.9581687 -0.07611 0.2031767 0.95783 -0.2031767 0.2031767 0.95783 -0.2031767 0.07389479 0.9579936 -0.2771059 0.07417577 0.9603113 -0.2688869 0.6940287 0.6940234 -0.1914564 0.6821739 0.707958 -0.1828504 0.4946855 0.7145437 -0.4946855 0.4946855 0.7145437 -0.4946855 0.1876068 0.7087336 -0.6800739 0.1862189 0.6947355 -0.694741 0.9324051 0.2610736 -0.2499225 0.9336825 0.2543331 -0.2520944 0.6852533 0.2466892 -0.6852533 0.6852534 0.2466892 -0.6852534 0.2503941 0.2542446 -0.9341641 0.2516342 0.2609541 -0.9319781 0 0 0 0 0.7071041 -0.7071095 0 0.7071041 -0.7071095 0 0.2696301 -0.9629639 0 0.2696301 -0.9629639 0.2696297 0.9629641 0 0.2696297 0.9629641 0 0.2696297 0.9629641 0 0.7071095 0.7071041 0 0.7071095 0.7071041 0 0.9629639 0.2696301 0 0.9629639 0.2696301 0 -0.07611 0.9581687 -0.2758985 -0.2031767 0.95783 -0.2031767 -0.2031767 0.95783 -0.2031767 -0.2771059 0.9579936 -0.07389479 -0.2688869 0.9603113 -0.07417577 -0.1914564 0.6940234 -0.6940287 -0.1828504 0.7079579 -0.6821739 -0.4946855 0.7145437 -0.4946855 -0.4946855 0.7145437 -0.4946855 -0.6800737 0.7087335 -0.1876068 -0.694741 0.6947355 -0.1862189 -0.2499225 0.2610736 -0.9324051 -0.2520944 0.2543331 -0.9336825 -0.6852533 0.2466892 -0.6852533 -0.6852534 0.2466892 -0.6852534 -0.9341641 0.2542446 -0.2503941 -0.9319781 0.2609541 -0.2516342 0.07171601 0.9604846 0.2689354 0.07611 0.9581687 0.2758985 0.2031767 0.95783 0.2031767 0.2031767 0.95783 0.2031767 0.2771059 0.9579936 0.07389479 0.2688869 0.9603113 0.07417577 0.1914564 0.6940234 0.6940287 0.1828504 0.7079579 0.6821739 0.4946855 0.7145437 0.4946855 0.4946855 0.7145437 0.4946855 0.6800737 0.7087335 0.1876068 0.694741 0.6947355 0.1862189 0.2499225 0.2610736 0.9324051 0.2520944 0.2543331 0.9336825 0.6852533 0.2466892 0.6852533 0.6852534 0.2466892 0.6852534 0.9341641 0.2542446 0.2503941 0.9319781 0.2609541 0.2516342 -0.2696297 0.9629641 0 -0.2696297 0.9629641 0 -0.2696297 0.9629641 0 -0.7071095 0.7071041 0 -0.7071095 0.7071041 0 -0.9629639 0.2696301 0 -0.9629639 0.2696301 0 0 0.9629641 0.2696297 0 0.9629641 0.2696297 0 0.9629641 0.2696297 0 0.7071041 0.7071095 0 0.7071041 0.7071095 0 0.2696301 0.9629639 0 0.2696301 0.9629639 -0.2689354 0.9604846 0.07171601 -0.2758985 0.9581687 0.07611 -0.2031767 0.95783 0.2031767 -0.2031767 0.95783 0.2031767 -0.07389479 0.9579936 0.2771059 -0.07417577 0.9603113 0.2688869 -0.6940287 0.6940234 0.1914564 -0.6821739 0.707958 0.1828504 -0.4946855 0.7145437 0.4946855 -0.4946855 0.7145437 0.4946855 -0.1876068 0.7087336 0.6800739 -0.1862189 0.6947355 0.694741 -0.9324051 0.2610736 0.2499225 -0.9336825 0.2543331 0.2520944 -0.6852533 0.2466892 0.6852533 -0.6852534 0.2466892 0.6852534 -0.2503941 0.2542446 0.9341641 -0.2516342 0.2609541 0.9319781 -0.9629639 0 -0.2696301 -0.9629639 0 -0.2696301 -0.7167251 0 -0.6973558 -0.7167237 -2.52567e-7 -0.6973572 -0.2516344 0 -0.9678224 -0.2516335 0 -0.9678226 -0.2516344 0 -0.9678224 -0.2516344 0 0.9678224 -0.2516344 0 0.9678224 -0.7167251 0 0.6973558 -0.7167251 0 0.6973558 -0.9629639 0 0.2696301 -0.9629639 0 0.2696301 -1 0 0 -1 0 0 0 0 1 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -0.9122474 0 0.4096398 -0.8835567 -0.01679629 -0.4680228 -0.957763 0.01149314 -0.2873293 -0.957763 0.01149314 0.2873293 -0.8835567 -0.01679629 0.4680228 -0.9086417 0.007449328 0.4175103 -0.881016 0.007450222 0.4730277 -0.8049004 -0.01266139 0.5932749 -0.9122221 0.007446944 -0.4096284 -0.901296 0 -0.4332039 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 -0.9190827 0.28875 -0.2681613 -0.9068856 0.3034356 -0.292379 -0.9189138 0.2091057 0.3344731 0.9175001 0.1444488 -0.3705781 0.8302804 0.1654177 -0.5322325 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.2516344 0 0.9678224 0.002348303 0.6348381 0.7726417 -0.7167251 0 0.6973558 -0.7167251 0 0.6973558 -0.2516344 0 0.9678224 -0.2516344 0 0.9678224 -0.2516344 0 -0.9678224 -0.2516344 0 -0.9678224 -0.7167251 0 -0.6973558 -0.004324674 0.7071006 -0.7070997 0.003669202 0.9127396 -0.4085254 0.2344187 0.967514 -0.09468168 -0.7256583 0.6450302 -0.2394912 -0.3975354 0.9086532 0.1277299 0.2290577 0.9690912 -0.09162318 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 0 0 0 0 0.03485059 -0.9993925 0.9993925 0.03485059 0 -0.9993925 0.03485059 0 -0.9993925 0.03485059 0 0 0 1 0 0 1 1 0 0 0 0 -1 -1 0 0 -1 0 0 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.260666 0 0.9654291 -0.9654291 0 0.260666 -0.9654291 0 0.260666 -0.9646556 0.04270696 0.2600302 -0.9645484 0.04270619 0.2604277 -0.706249 0.04924374 0.7062489 -0.7062489 0.04924374 0.7062489 -0.2604277 0.04270619 0.9645484 -0.2600302 0.04270696 0.9646556 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.260666 0 -0.9654291 -0.2600301 0.04270696 -0.9646555 -0.2604277 0.04270619 -0.9645484 -0.7062489 0.04924374 -0.706249 -0.7062489 0.04924374 -0.7062489 0.260666 0 -0.9654291 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.260666 0 -0.9654291 0.9654291 0 -0.260666 0.9646556 0.04270696 -0.2600302 0.9645484 0.04270619 -0.2604277 0.706249 0.04924374 -0.7062489 0.7062489 0.04924374 -0.7062489 0.2600302 0.04270696 -0.9646556 0.2604278 0.04270619 0.9645484 0.2600301 0.04270696 0.9646556 0.9645479 0.04271709 0.2604277 0.964656 0.04269605 0.2600303 0.7062489 0.04924374 0.7062489 0.706249 0.04924374 0.7062489 0.7071068 0 0.7071068 0.9654291 0 0.260666 0.9654291 0 0.260666 0.260666 0 0.9654291 0.260666 0 0.9654291 0 0 0 0 0 0 -1.5404e-7 1 -6.36081e-7 3.24032e-7 1 5.61656e-7 6.54708e-7 1 0 -6.48629e-7 1 0 -5.82531e-7 1 2.98564e-7 4.26935e-7 1 4.96095e-7 -3.27791e-7 1 5.66667e-7 6.28108e-7 1 1.84581e-7 -1.5404e-7 1 6.36081e-7 5.49908e-7 1 -3.55121e-7 5.49908e-7 1 3.55121e-7 -4.74061e-7 1 -4.51486e-7 0 1 6.53629e-7 2.16121e-7 1 -6.17868e-7 3.24032e-7 1 -5.61656e-7 -5.82531e-7 1 -2.98564e-7 -4.74061e-7 1 4.51486e-7 4.26935e-7 1 -4.96095e-7 -3.27791e-7 1 -5.66667e-7 -6.43363e-7 1 1.20963e-7 2.16121e-7 1 6.17868e-7 6.28108e-7 1 -1.84581e-7 -6.43363e-7 1 -1.20963e-7 0 1 -6.53629e-7 0 0.9629641 -0.2696297 0 0.9629641 -0.2696297 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -0.1872387 -0.9823144 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -0.1364855 -0.9817008 -0.1327975 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -0.08765232 -0.9373711 -0.3371237 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -0.1734797 -0.9848374 0 0 0 0 0 0 0 0 0 0 -0.1734797 -0.9848374 0 0 0 0 0 0 0 0 0.9629641 -0.2696297 0 0 0 -0.07171601 0.9604846 -0.2689354 -0.08764123 -0.9899891 0.1106374 0.07545632 -0.9970984 0.01005166 -0.165484 -0.9851234 -0.04633498 0.06710433 -0.9963871 -0.05205571 -0.01855289 -0.9915714 -0.1282264 -0.1596735 -0.9861569 0.0447086 0.01166564 -0.9952132 0.09702873 0.1506127 0.98234 0.1110134 0.01357448 -0.9934884 -0.1131218 0 0 0 -0.1199531 -0.9858954 0.1167114 0.0334047 -0.9960209 0.08262425 0.07395762 -0.9967855 -0.03080356 -0.1550459 -0.986953 0.04341232 -0.04902708 -0.9923275 0.1135011 -0.05939245 -0.9717465 0.2284322 0.01359909 -0.9934894 -0.1131098 0 0 0 -0.1297165 -0.9869306 0.09561127 0.05006933 -0.9965522 0.06615769 0.07658731 -0.9970107 -0.01020228 -0.1044685 -0.9857454 -0.1318801 0.1044685 0.9857454 0.1318801 0 -0.9662557 0.2575849 -0.01562213 -0.9940313 0.1079711 -0.1443563 -0.9795069 -0.1404551 0.03801149 -0.9948446 -0.09401881 0.06233876 -0.9968829 0.04835891 -0.05876457 -0.9889584 -0.136044 -0.05089199 -0.9793348 0.195738 0.01164436 -0.9952126 0.09703755 -0.1872387 -0.9823144 0 0.05545455 -0.995769 -0.0732733 -0.1144365 -0.9871711 0.1113438 0.07075601 -0.9970582 0.02947002 -0.1506127 -0.98234 -0.1110134 0.05876457 0.9889584 0.136044 -0.1603716 -0.9844262 0.07201397 -0.01855289 -0.9915714 -0.1282265 0 0.03485065 0.9993925 0 0.03485059 0.9993926 0 0.03485053 0.9993925 0 0.03485059 0.9993926 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.1707559 -0.9841526 -0.04781168 0.070692 0.9597275 0.2718927 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0.1790391 0.9805517 0.08039653 -0.1790391 -0.9805517 -0.08039653 0 -0.9156407 -0.4019977 + + + + + + + + + + + + + + + + +3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 4 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 4 4 4 4 4 4 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 4 4 4 4 4 4 3 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 3 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 3 4 4 4 4 4 4 4 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 + +

+376 0 371 0 375 0 325 1 326 1 329 1 161 2 75 2 120 2 122 3 76 3 284 3 277 4 404 4 278 4 278 5 404 5 280 5 280 6 404 6 406 6 280 7 406 7 282 7 408 8 275 8 406 8 406 9 275 9 281 9 406 10 281 10 282 10 410 11 259 11 408 11 408 12 259 12 266 12 408 13 266 13 275 13 414 14 263 14 264 14 414 15 264 15 412 15 412 16 264 16 262 16 412 17 262 17 410 17 410 18 262 18 260 18 410 19 260 19 259 19 263 20 414 20 257 20 257 21 414 21 416 21 257 22 416 22 248 22 248 23 416 23 241 23 241 24 416 24 418 24 241 25 418 25 242 25 420 26 246 26 418 26 418 27 246 27 244 27 418 28 244 28 242 28 230 29 234 29 423 29 423 30 234 30 239 30 423 31 239 31 420 31 420 32 239 32 245 32 420 33 245 33 246 33 230 34 423 34 229 34 229 35 423 35 422 35 229 36 422 36 221 36 221 37 422 37 214 37 214 38 422 38 421 38 214 39 421 39 215 39 215 40 421 40 217 40 217 41 421 41 419 41 217 42 419 42 219 42 417 43 212 43 419 43 419 44 212 44 218 44 419 45 218 45 219 45 199 46 197 46 415 46 415 47 197 47 196 47 415 48 196 48 417 48 417 49 196 49 203 49 417 50 203 50 212 50 199 51 415 51 201 51 201 52 415 52 413 52 201 53 413 53 200 53 200 54 413 54 194 54 194 55 413 55 411 55 194 56 411 56 185 56 185 57 411 57 409 57 185 58 409 58 178 58 178 59 409 59 407 59 178 60 407 60 179 60 405 61 183 61 407 61 407 62 183 62 181 62 407 63 181 63 179 63 167 64 171 64 403 64 403 65 171 65 176 65 403 66 176 66 405 66 405 67 176 67 182 67 405 68 182 68 183 68 167 69 403 69 166 69 166 70 403 70 402 70 166 71 402 71 162 71 84 72 76 72 122 72 122 73 123 73 84 73 84 74 123 74 150 74 84 75 150 75 151 75 151 76 124 76 84 76 126 77 125 77 84 77 84 78 125 78 27 78 84 79 27 79 82 79 118 80 117 80 107 80 107 81 106 81 28 81 120 82 107 82 121 82 121 83 107 83 119 83 118 84 107 84 130 84 130 85 107 85 28 85 130 86 28 86 129 86 41 87 40 87 127 87 31 88 30 88 173 88 114 89 74 89 36 89 28 90 106 90 34 90 108 91 35 91 110 91 110 92 35 92 34 92 110 93 34 93 109 93 109 94 34 94 106 94 108 95 111 95 35 95 36 96 116 96 114 96 78 97 40 97 80 97 80 98 40 98 79 98 40 99 81 99 83 99 125 100 127 100 27 100 27 101 127 101 40 101 27 102 40 102 82 102 82 103 40 103 83 103 79 104 40 104 77 104 77 105 40 105 39 105 77 106 39 106 73 106 73 107 39 107 38 107 73 108 38 108 74 108 74 109 38 109 37 109 74 110 37 110 36 110 173 111 30 111 152 111 152 112 30 112 29 112 152 113 29 113 188 113 188 114 29 114 71 114 188 115 71 115 190 115 190 116 71 116 72 116 190 117 72 117 134 117 173 118 133 118 31 118 31 119 133 119 169 119 31 120 169 120 32 120 32 121 169 121 164 121 32 122 164 122 33 122 33 123 164 123 132 123 33 124 132 124 34 124 34 125 132 125 159 125 34 126 159 126 28 126 28 127 159 127 131 127 28 128 131 128 129 128 127 129 128 129 41 129 41 130 128 130 148 130 41 131 148 131 42 131 42 132 148 132 291 132 42 133 291 133 43 133 43 134 291 134 289 134 43 135 289 135 44 135 44 136 289 136 158 136 44 137 158 137 45 137 158 138 157 138 45 138 45 139 157 139 272 139 45 140 272 140 46 140 46 141 272 141 146 141 46 142 146 142 47 142 47 143 146 143 147 143 47 144 147 144 48 144 48 145 147 145 271 145 48 146 271 146 49 146 49 147 271 147 269 147 49 148 269 148 50 148 269 149 156 149 50 149 50 150 156 150 155 150 50 151 155 151 51 151 51 152 155 152 254 152 51 153 254 153 52 153 52 154 254 154 144 154 52 155 144 155 53 155 53 156 144 156 145 156 53 157 145 157 54 157 145 158 253 158 54 158 54 159 253 159 251 159 54 160 251 160 55 160 55 161 251 161 154 161 55 162 154 162 56 162 56 163 154 163 236 163 56 164 236 164 57 164 57 165 236 165 143 165 57 166 143 166 58 166 143 167 232 167 58 167 58 168 232 168 142 168 58 169 142 169 59 169 59 170 142 170 227 170 59 171 227 171 60 171 60 172 227 172 140 172 60 173 140 173 61 173 61 174 140 174 141 174 61 175 141 175 62 175 141 176 226 176 62 176 62 177 226 177 224 177 62 178 224 178 63 178 64 179 209 179 139 179 64 180 139 180 65 180 65 181 139 181 138 181 65 182 138 182 66 182 66 183 138 183 137 183 66 184 137 184 67 184 67 185 137 185 208 185 67 186 208 186 68 186 208 187 206 187 68 187 68 188 206 188 153 188 68 189 153 189 69 189 69 190 153 190 191 190 69 191 191 191 70 191 70 192 191 192 136 192 70 193 136 193 72 193 72 194 136 194 135 194 72 195 135 195 134 195 71 196 308 196 309 196 71 197 29 197 308 197 308 198 29 198 30 198 308 199 30 199 292 199 30 200 31 200 292 200 292 201 31 201 32 201 292 202 32 202 307 202 32 203 33 203 307 203 307 204 33 204 34 204 307 205 34 205 306 205 34 206 35 206 306 206 306 207 35 207 36 207 306 208 36 208 305 208 36 209 37 209 305 209 305 210 37 210 38 210 305 211 38 211 304 211 38 212 39 212 304 212 304 213 39 213 40 213 304 214 40 214 303 214 40 215 41 215 303 215 303 216 41 216 42 216 303 217 42 217 302 217 42 218 43 218 302 218 302 219 43 219 44 219 302 220 44 220 301 220 44 221 45 221 301 221 301 222 45 222 46 222 301 223 46 223 293 223 46 224 47 224 293 224 293 225 47 225 48 225 293 226 48 226 294 226 48 227 49 227 294 227 294 228 49 228 50 228 294 229 50 229 295 229 50 230 51 230 295 230 295 231 51 231 52 231 295 232 52 232 296 232 52 233 53 233 296 233 296 234 53 234 54 234 296 235 54 235 297 235 54 236 55 236 297 236 297 237 55 237 56 237 297 238 56 238 298 238 56 239 57 239 298 239 298 240 57 240 58 240 298 241 58 241 299 241 58 242 59 242 299 242 299 243 59 243 60 243 299 244 60 244 300 244 60 245 61 245 300 245 300 246 61 246 62 246 300 247 62 247 313 247 62 248 63 248 313 248 313 249 63 249 64 249 313 250 64 250 312 250 64 251 65 251 312 251 312 252 65 252 66 252 312 253 66 253 311 253 66 254 67 254 311 254 311 255 67 255 68 255 311 256 68 256 310 256 68 257 69 257 310 257 310 258 69 258 70 258 310 259 70 259 309 259 309 260 70 260 72 260 309 261 72 261 71 261 399 262 95 262 398 262 398 263 95 263 99 263 398 264 99 264 397 264 93 265 77 265 73 265 93 266 73 266 115 266 115 267 73 267 74 267 115 268 74 268 114 268 77 269 93 269 79 269 79 270 93 270 89 270 85 271 78 271 89 271 89 272 78 272 80 272 89 273 80 273 79 273 81 274 85 274 83 274 83 275 85 275 84 275 83 276 84 276 82 276 95 277 399 277 401 277 95 278 401 278 92 278 84 279 87 279 88 279 86 280 87 280 84 280 85 281 86 281 84 281 85 282 89 282 86 282 86 283 89 283 90 283 86 284 90 284 87 284 87 285 90 285 91 285 87 286 91 286 88 286 88 287 91 287 92 287 89 288 93 288 90 288 90 289 93 289 94 289 90 290 94 290 91 290 91 291 94 291 96 291 91 292 96 292 92 292 92 293 96 293 95 293 93 294 115 294 97 294 93 295 97 295 94 295 94 296 97 296 98 296 94 297 98 297 96 297 96 298 98 298 99 298 96 299 99 299 95 299 105 300 400 300 103 300 103 301 400 301 397 301 103 302 397 302 99 302 101 303 112 303 107 303 101 304 107 304 104 304 115 305 113 305 97 305 97 306 113 306 100 306 97 307 100 307 98 307 98 308 100 308 102 308 98 309 102 309 99 309 99 310 102 310 103 310 113 311 112 311 100 311 100 312 112 312 101 312 100 313 101 313 102 313 102 314 101 314 104 314 102 315 104 315 103 315 103 316 104 316 105 316 105 317 104 317 107 317 106 318 107 318 109 318 109 319 107 319 112 319 111 320 108 320 112 320 112 321 108 321 110 321 112 322 110 322 109 322 116 323 113 323 115 323 116 324 115 324 114 324 268 325 274 325 276 325 250 326 256 326 258 326 223 327 228 327 231 327 205 328 211 328 213 328 187 329 193 329 195 329 158 330 289 330 290 330 272 331 157 331 273 331 156 332 269 332 270 332 254 333 155 333 255 333 154 334 251 334 252 334 153 335 206 335 207 335 173 336 152 336 174 336 164 337 169 337 170 337 163 338 117 338 160 338 160 339 117 339 118 339 160 340 118 340 130 340 119 341 163 341 121 341 121 342 163 342 161 342 121 343 161 343 120 343 122 344 284 344 123 344 123 345 284 345 286 345 123 346 286 346 150 346 149 347 124 347 151 347 125 348 126 348 127 348 127 349 126 349 149 349 127 350 149 350 128 350 128 351 149 351 148 351 159 352 160 352 131 352 131 353 160 353 130 353 131 354 130 354 129 354 159 355 132 355 165 355 165 356 132 356 164 356 169 357 133 357 175 357 175 358 133 358 173 358 190 359 134 359 187 359 187 360 134 360 135 360 187 361 135 361 193 361 193 362 135 362 136 362 193 363 136 363 191 363 208 364 137 364 205 364 205 365 137 365 138 365 205 366 138 366 211 366 211 367 138 367 139 367 211 368 139 368 209 368 227 369 228 369 140 369 140 370 228 370 223 370 140 371 223 371 141 371 141 372 223 372 226 372 227 373 142 373 233 373 233 374 142 374 232 374 232 375 143 375 238 375 238 376 143 376 236 376 254 377 256 377 144 377 144 378 256 378 250 378 144 379 250 379 145 379 145 380 250 380 253 380 272 381 274 381 146 381 146 382 274 382 268 382 146 383 268 383 147 383 147 384 268 384 271 384 291 385 148 385 288 385 288 386 148 386 149 386 288 387 149 387 286 387 286 388 149 388 151 388 286 389 151 389 150 389 180 390 184 390 174 390 152 391 188 391 174 391 174 392 188 392 189 392 174 393 189 393 180 393 180 394 189 394 186 394 180 395 186 395 178 395 178 396 186 396 185 396 198 397 202 397 192 397 191 398 153 398 192 398 192 399 153 399 207 399 192 400 207 400 198 400 198 401 207 401 204 401 198 402 204 402 196 402 196 403 204 403 203 403 216 404 220 404 210 404 210 405 225 405 216 405 216 406 225 406 222 406 243 407 247 407 237 407 236 408 154 408 237 408 237 409 154 409 252 409 237 410 252 410 243 410 243 411 252 411 249 411 243 412 249 412 241 412 241 413 249 413 248 413 261 414 265 414 255 414 155 415 156 415 255 415 255 416 156 416 270 416 255 417 270 417 261 417 261 418 270 418 267 418 261 419 267 419 259 419 259 420 267 420 266 420 279 421 283 421 273 421 157 422 158 422 273 422 273 423 158 423 290 423 273 424 290 424 279 424 279 425 290 425 287 425 168 426 166 426 162 426 159 427 165 427 160 427 160 428 165 428 168 428 160 429 168 429 163 429 163 430 168 430 162 430 163 431 162 431 161 431 172 432 171 432 167 432 164 433 170 433 165 433 165 434 170 434 172 434 165 435 172 435 168 435 168 436 172 436 167 436 168 437 167 437 166 437 169 438 175 438 170 438 170 439 175 439 177 439 170 440 177 440 172 440 172 441 177 441 176 441 172 442 176 442 171 442 173 443 174 443 175 443 175 444 174 444 184 444 175 445 184 445 177 445 177 446 184 446 182 446 177 447 182 447 176 447 178 448 179 448 180 448 180 449 179 449 181 449 180 450 181 450 184 450 184 451 181 451 183 451 184 452 183 452 182 452 194 453 185 453 195 453 195 454 185 454 186 454 195 455 186 455 187 455 187 456 186 456 189 456 187 457 189 457 190 457 190 458 189 458 188 458 191 459 192 459 193 459 193 460 192 460 202 460 193 461 202 461 195 461 195 462 202 462 200 462 195 463 200 463 194 463 196 464 197 464 198 464 198 465 197 465 199 465 198 466 199 466 202 466 202 467 199 467 201 467 202 468 201 468 200 468 212 469 203 469 213 469 213 470 203 470 204 470 213 471 204 471 205 471 205 472 204 472 207 472 205 473 207 473 208 473 208 474 207 474 206 474 209 475 210 475 211 475 211 476 210 476 220 476 211 477 220 477 213 477 213 478 220 478 218 478 213 479 218 479 212 479 221 480 214 480 222 480 222 481 214 481 215 481 222 482 215 482 216 482 216 483 215 483 217 483 216 484 217 484 220 484 220 485 217 485 219 485 220 486 219 486 218 486 229 487 221 487 231 487 231 488 221 488 222 488 231 489 222 489 223 489 223 490 222 490 225 490 223 491 225 491 226 491 226 492 225 492 224 492 235 493 234 493 230 493 227 494 233 494 228 494 228 495 233 495 235 495 228 496 235 496 231 496 231 497 235 497 230 497 231 498 230 498 229 498 232 499 238 499 233 499 233 500 238 500 240 500 233 501 240 501 235 501 235 502 240 502 239 502 235 503 239 503 234 503 236 504 237 504 238 504 238 505 237 505 247 505 238 506 247 506 240 506 240 507 247 507 245 507 240 508 245 508 239 508 241 509 242 509 243 509 243 510 242 510 244 510 243 511 244 511 247 511 247 512 244 512 246 512 247 513 246 513 245 513 257 514 248 514 258 514 258 515 248 515 249 515 258 516 249 516 250 516 250 517 249 517 252 517 250 518 252 518 253 518 253 519 252 519 251 519 254 520 255 520 256 520 256 521 255 521 265 521 256 522 265 522 258 522 258 523 265 523 263 523 258 524 263 524 257 524 259 525 260 525 261 525 261 526 260 526 262 526 261 527 262 527 265 527 265 528 262 528 264 528 265 529 264 529 263 529 275 530 266 530 276 530 276 531 266 531 267 531 276 532 267 532 268 532 268 533 267 533 270 533 268 534 270 534 271 534 271 535 270 535 269 535 272 536 273 536 274 536 274 537 273 537 283 537 274 538 283 538 276 538 276 539 283 539 281 539 276 540 281 540 275 540 285 541 277 541 287 541 287 542 277 542 278 542 287 543 278 543 279 543 279 544 278 544 280 544 279 545 280 545 283 545 283 546 280 546 282 546 283 547 282 547 281 547 284 548 285 548 286 548 286 549 285 549 287 549 286 550 287 550 288 550 288 551 287 551 290 551 288 552 290 552 291 552 291 553 290 553 289 553 301 554 293 554 389 554 308 555 292 555 363 555 363 556 292 556 307 556 389 557 293 557 385 557 385 558 293 558 294 558 385 559 294 559 380 559 380 560 294 560 295 560 380 561 295 561 377 561 377 562 295 562 296 562 377 563 296 563 373 563 373 564 296 564 297 564 373 565 297 565 370 565 370 566 297 566 298 566 370 567 298 567 390 567 390 568 298 568 299 568 390 569 299 569 393 569 393 570 299 570 300 570 393 571 300 571 313 571 389 572 387 572 301 572 301 573 387 573 365 573 301 574 365 574 302 574 302 575 365 575 342 575 302 576 342 576 303 576 303 577 342 577 345 577 303 578 345 578 304 578 304 579 345 579 351 579 304 580 351 580 305 580 305 581 351 581 354 581 305 582 354 582 306 582 306 583 354 583 357 583 306 584 357 584 307 584 307 585 357 585 359 585 307 586 359 586 363 586 363 587 337 587 308 587 308 588 337 588 315 588 308 589 315 589 309 589 309 590 315 590 319 590 309 591 319 591 310 591 310 592 319 592 324 592 310 593 324 593 311 593 311 594 324 594 327 594 311 595 327 595 312 595 312 596 327 596 330 596 312 597 330 597 313 597 313 598 330 598 334 598 313 599 334 599 393 599 317 600 314 600 319 600 314 601 315 601 319 601 314 602 316 602 315 602 316 603 337 603 315 603 316 604 336 604 337 604 317 605 319 605 318 605 319 606 320 606 318 606 319 607 320 607 324 607 324 608 321 608 320 608 324 609 322 609 321 609 322 610 324 610 323 610 324 611 325 611 323 611 324 612 327 612 325 612 325 613 327 613 326 613 327 614 329 614 326 614 327 615 330 615 329 615 333 616 328 616 334 616 328 617 330 617 334 617 328 618 331 618 330 618 331 619 329 619 330 619 392 620 393 620 332 620 332 621 393 621 334 621 332 622 335 622 334 622 335 623 333 623 334 623 361 624 338 624 363 624 364 625 365 625 339 625 365 626 340 626 339 626 365 627 342 627 340 627 340 628 342 628 341 628 342 629 343 629 341 629 342 630 345 630 343 630 343 631 345 631 344 631 345 632 346 632 344 632 345 633 351 633 346 633 346 634 351 634 347 634 351 635 348 635 347 635 351 636 349 636 348 636 349 637 351 637 350 637 351 638 352 638 350 638 351 639 354 639 352 639 352 640 354 640 353 640 354 641 355 641 353 641 354 642 357 642 355 642 355 643 357 643 356 643 357 644 358 644 356 644 357 645 358 645 359 645 359 646 358 646 360 646 359 647 360 647 363 647 363 648 360 648 362 648 363 649 362 649 361 649 372 650 370 650 373 650 390 651 366 651 391 651 366 652 390 652 367 652 390 653 368 653 367 653 390 654 370 654 368 654 370 655 369 655 368 655 370 656 372 656 369 656 375 657 371 657 377 657 371 658 373 658 377 658 371 659 374 659 373 659 374 660 372 660 373 660 375 661 377 661 376 661 377 662 378 662 376 662 377 663 380 663 378 663 378 664 380 664 379 664 380 665 381 665 379 665 380 666 385 666 381 666 385 667 382 667 381 667 385 668 383 668 382 668 383 669 385 669 384 669 385 670 386 670 384 670 385 671 389 671 386 671 389 672 388 672 386 672 389 673 388 673 387 673 559 708 557 708 593 708 595 708 6 787 26 787 3 787 6 788 22 788 26 788 8 789 22 789 6 789 8 790 20 790 22 790 11 791 20 791 8 791 11 792 18 792 20 792 25 793 0 793 2 793 1 794 24 794 4 794 9 795 19 795 10 795 7 796 19 796 9 796 7 797 21 797 19 797 5 798 21 798 7 798 5 799 23 799 21 799 23 800 4 800 24 800 5 801 4 801 23 801 10 802 15 802 12 802 18 803 13 803 14 803 11 804 13 804 18 804 3 805 25 805 2 805 26 806 25 806 3 806 16 807 15 807 17 807 162 808 13 808 161 808 161 809 13 809 75 809 284 810 76 810 16 810 284 811 16 811 285 811 285 812 16 812 17 812 285 813 17 813 277 813 277 814 17 814 404 814 162 815 402 815 14 815 162 816 14 816 13 816 4 817 76 817 84 817 84 818 124 818 126 818 107 819 117 819 119 819 75 820 2 820 120 820 120 821 2 821 107 821 35 822 111 822 36 822 36 823 111 823 116 823 78 824 81 824 40 824 63 825 224 825 209 825 63 826 209 826 64 826 75 827 13 827 11 827 2 828 75 828 3 828 3 829 75 829 11 829 3 830 11 830 6 830 6 831 11 831 8 831 12 832 15 832 16 832 16 833 76 833 12 833 12 834 76 834 4 834 12 835 4 835 9 835 9 836 4 836 5 836 9 837 5 837 7 837 9 838 10 838 12 838 85 839 81 839 78 839 92 840 401 840 1 840 92 841 1 841 88 841 88 842 1 842 4 842 88 843 4 843 84 843 105 844 107 844 2 844 2 845 0 845 105 845 105 846 0 846 400 846 111 847 112 847 113 847 111 848 113 848 116 848 209 849 224 849 225 849 163 850 119 850 117 850 126 851 124 851 149 851 210 852 209 852 225 852 550 859 548 859 407 859 409 859 544 860 543 860 402 860 403 860 545 868 534 868 570 868 581 868 423 869 420 869 561 869 564 869 590 919 588 919 552 919 554 919 558 920 556 920 415 920 417 920 530 921 385 921 380 921 530 922 337 922 363 922 530 923 354 923 351 923 530 924 390 924 393 924 530 925 334 925 330 925 530 926 363 926 359 926 530 927 327 927 324 927 530 928 357 928 354 928 530 929 324 929 319 929 530 930 345 930 342 930 530 931 359 931 357 931 530 932 377 932 373 932 530 933 319 933 315 933 389 934 530 934 387 934 530 935 365 935 387 935 530 936 373 936 370 936 530 937 330 937 327 937 365 938 530 938 342 938 530 939 380 939 377 939 530 940 393 940 334 940 337 941 530 941 315 941 530 942 351 942 345 942 390 943 530 943 370 943 530 944 389 944 385 944 395 947 574 947 538 947 531 947 414 948 412 948 553 948 555 948 1 949 401 949 542 949 531 949 536 950 535 950 19 950 21 950 560 951 558 951 417 951 419 951 541 952 539 952 397 952 400 952 25 953 26 953 644 953 535 954 532 954 10 954 19 954 476 955 477 955 567 955 566 955 422 956 423 956 564 956 563 956 406 957 404 957 545 957 547 957 552 958 550 958 409 958 411 958 416 959 414 959 555 959 557 959 531 960 538 960 24 960 1 960 537 961 536 961 21 961 23 961 562 962 560 962 419 962 421 962 401 963 399 963 540 963 542 963 408 964 406 964 547 964 549 964 554 965 552 965 411 965 413 965 400 966 0 966 479 966 541 966 533 967 534 967 17 967 15 967 418 968 416 968 557 968 559 968 23 969 24 969 538 969 537 969 475 970 476 970 566 970 565 970 421 971 422 971 563 971 562 971 546 972 544 972 403 972 405 972 404 973 17 973 534 973 545 973 410 974 408 974 549 974 551 974 556 975 554 975 413 975 415 975 532 976 533 976 15 976 10 976 420 977 418 977 559 977 561 977 409 978 475 978 565 978 550 978 477 979 478 979 568 979 567 979 548 980 546 980 405 980 407 980 412 981 410 981 551 981 553 981 587 982 585 982 624 982 626 982 605 983 608 983 569 983 394 983 602 984 603 984 642 984 641 984 621 985 619 985 580 985 582 985 598 986 599 986 638 986 637 986 595 987 593 987 632 987 634 987 581 988 570 988 609 988 620 988 573 989 572 989 536 989 537 989 562 990 563 990 599 990 598 990 582 991 580 991 544 991 546 991 566 992 567 992 603 992 602 992 394 993 569 993 533 993 532 993 551 994 549 994 585 994 587 994 396 995 577 995 541 995 479 995 592 996 590 996 554 996 556 996 561 997 559 997 595 997 597 997 537 998 538 998 574 998 573 998 584 999 582 999 546 999 548 999 571 1000 394 1000 532 1000 535 1000 553 1001 551 1001 587 1001 589 1001 594 1002 592 1002 556 1002 558 1002 564 1003 561 1003 597 1003 600 1003 580 1004 579 1004 543 1004 544 1004 565 1005 566 1005 602 1005 601 1005 569 1006 570 1006 534 1006 533 1006 586 1007 584 1007 548 1007 550 1007 555 1008 553 1008 589 1008 591 1008 550 1009 565 1009 601 1009 586 1009 596 1010 594 1010 558 1010 560 1010 577 1011 575 1011 539 1011 541 1011 644 1012 22 1012 20 1012 563 1013 564 1013 600 1013 599 1013 547 1014 545 1014 581 1014 583 1014 567 1015 568 1015 604 1015 603 1015 572 1016 571 1016 535 1016 536 1016 588 1017 586 1017 550 1017 552 1017 531 1018 542 1018 578 1018 395 1018 557 1019 555 1019 591 1019 593 1019 598 1020 596 1020 560 1020 562 1020 542 1021 540 1021 576 1021 578 1021 549 1022 547 1022 583 1022 585 1022 607 1023 616 1023 577 1023 396 1023 631 1024 629 1024 590 1024 592 1024 597 1025 595 1025 634 1025 636 1025 623 1026 621 1026 582 1026 584 1026 610 1027 605 1027 394 1027 571 1027 589 1028 587 1028 626 1028 628 1028 573 1029 574 1029 613 1029 612 1029 633 1030 631 1030 592 1030 594 1030 611 1031 610 1031 571 1031 572 1031 600 1032 597 1032 636 1032 639 1032 619 1033 618 1033 579 1033 580 1033 601 1034 602 1034 641 1034 640 1034 608 1035 609 1035 570 1035 569 1035 625 1036 623 1036 584 1036 586 1036 591 1037 589 1037 628 1037 630 1037 612 1038 611 1038 572 1038 573 1038 586 1039 601 1039 640 1039 625 1039 635 1040 633 1040 594 1040 596 1040 616 1041 614 1041 575 1041 577 1041 599 1042 600 1042 639 1042 638 1042 583 1043 581 1043 620 1043 622 1043 603 1044 604 1044 643 1044 642 1044 627 1045 625 1045 586 1045 588 1045 607 1046 25 1046 644 1046 395 1047 578 1047 617 1047 606 1047 593 1048 591 1048 630 1048 632 1048 637 1049 635 1049 596 1049 598 1049 578 1050 576 1050 615 1050 617 1050 585 1051 583 1051 622 1051 624 1051 606 1052 613 1052 574 1052 395 1052 629 1053 627 1053 588 1053 590 1053 396 1054 25 1054 607 1054 644 1055 615 1055 398 1055 398 1056 615 1056 576 1056 614 1057 398 1057 575 1057 398 1058 540 1058 399 1058 644 1059 398 1059 614 1059 398 1060 576 1060 540 1060 539 1061 398 1061 397 1061 575 1063 398 1063 539 1063 622 1065 620 1065 644 1065 638 1066 639 1066 644 1066 644 1067 614 1067 616 1067 644 1068 633 1068 635 1068 625 1069 644 1069 640 1069 644 1070 611 1070 612 1070 630 1071 628 1071 644 1071 642 1072 643 1072 644 1072 644 1073 625 1073 627 1073 479 1074 25 1074 396 1074 606 1075 617 1075 644 1075 632 1076 630 1076 644 1076 644 1077 635 1077 637 1077 617 1078 615 1078 644 1078 624 1079 622 1079 644 1079 644 1080 613 1080 606 1080 644 1081 627 1081 629 1081 0 1082 25 1082 479 1082 620 1083 609 1083 644 1083 634 1084 632 1084 644 1084 637 1085 638 1085 644 1085 644 1086 619 1086 621 1086 641 1087 642 1087 644 1087 644 1088 608 1088 605 1088 626 1089 624 1089 644 1089 644 1090 616 1090 607 1090 644 1091 629 1091 631 1091 636 1092 634 1092 644 1092 644 1093 621 1093 623 1093 644 1094 605 1094 610 1094 628 1095 626 1095 644 1095 612 1096 613 1096 644 1096 644 1097 631 1097 633 1097 644 1098 610 1098 611 1098 639 1099 636 1099 644 1099 644 1100 618 1100 619 1100 640 1101 641 1101 644 1101 644 1102 609 1102 608 1102 644 1103 623 1103 625 1103 26 1128 22 1128 644 1128 644 1129 18 1129 20 1129 543 1130 14 1130 402 1130 478 1131 14 1131 568 1131 568 1132 14 1132 604 1132 579 1133 14 1133 543 1133 604 1134 14 1134 643 1134 618 1135 14 1135 579 1135 643 1136 14 1136 644 1136 644 1137 14 1137 618 1137 18 1138 14 1138 644 1138 +

+
+ + + + +3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 + +

+453 674 526 674 528 674 453 675 503 675 524 675 453 676 449 676 503 676 503 677 449 677 466 677 529 678 528 678 520 678 523 679 521 679 522 679 483 680 481 680 468 680 467 681 469 681 457 681 430 682 432 682 439 682 439 683 441 683 430 683 466 684 456 684 468 684 426 685 424 685 441 685 441 686 424 686 430 686 520 687 514 687 522 687 497 688 524 688 503 688 498 689 515 689 500 689 505 690 516 690 501 690 501 691 516 691 508 691 501 692 508 692 491 692 491 693 508 693 493 693 491 694 493 694 489 694 489 695 493 695 487 695 516 696 518 696 508 696 508 697 518 697 510 697 508 698 510 698 493 698 493 699 510 699 495 699 493 700 495 700 487 700 487 701 495 701 485 701 518 702 522 702 510 702 510 703 522 703 514 703 510 704 514 704 495 704 495 705 514 705 499 705 495 706 499 706 485 706 485 707 499 707 483 707 472 709 487 709 485 709 472 710 485 710 470 710 470 711 485 711 483 711 470 712 483 712 468 712 506 713 507 713 517 713 516 714 505 714 506 714 506 715 517 715 516 715 516 716 517 716 519 716 516 717 519 717 518 717 518 718 519 718 523 718 518 719 523 719 522 719 464 720 472 720 460 720 464 721 460 721 451 721 451 722 460 722 444 722 451 723 444 723 446 723 446 724 444 724 436 724 472 725 470 725 460 725 460 726 470 726 458 726 460 727 458 727 444 727 444 728 458 728 442 728 444 729 442 729 436 729 436 730 442 730 434 730 470 731 468 731 458 731 458 732 468 732 456 732 458 733 456 733 442 733 442 734 456 734 439 734 442 735 439 735 434 735 434 736 439 736 432 736 490 737 488 737 492 737 492 738 488 738 494 738 492 739 494 739 502 739 502 740 494 740 509 740 502 741 509 741 507 741 507 742 509 742 517 742 488 743 486 743 494 743 494 744 486 744 496 744 494 745 496 745 509 745 509 746 496 746 511 746 509 747 511 747 517 747 517 748 511 748 519 748 486 749 484 749 496 749 496 750 484 750 500 750 496 751 500 751 511 751 511 752 500 752 515 752 511 753 515 753 519 753 519 754 515 754 523 754 447 755 446 755 436 755 437 756 448 756 447 756 447 757 436 757 437 757 437 758 436 758 434 758 437 759 434 759 435 759 435 760 434 760 432 760 435 761 432 761 433 761 480 762 474 762 473 762 488 763 490 763 480 763 480 764 473 764 488 764 488 765 473 765 471 765 488 766 471 766 486 766 486 767 471 767 469 767 486 768 469 768 484 768 448 769 437 769 452 769 452 770 437 770 445 770 452 771 445 771 465 771 465 772 445 772 461 772 465 773 461 773 474 773 474 774 461 774 473 774 437 775 435 775 445 775 445 776 435 776 443 776 445 777 443 777 461 777 461 778 443 778 459 778 461 779 459 779 473 779 473 780 459 780 471 780 435 781 433 781 443 781 443 782 433 782 440 782 443 783 440 783 459 783 459 784 440 784 457 784 459 785 457 785 471 785 471 786 457 786 469 786 529 853 527 853 453 853 450 854 429 854 453 854 528 855 529 855 453 855 429 856 427 856 453 856 525 857 504 857 453 857 504 858 450 858 453 858 453 861 425 861 424 861 453 862 428 862 449 862 453 863 426 863 428 863 453 864 424 864 426 864 527 865 525 865 453 865 453 866 524 866 526 866 427 867 425 867 453 867 503 870 466 870 481 870 529 871 520 871 521 871 424 872 425 872 431 872 424 873 431 873 430 873 469 874 467 874 484 874 484 875 467 875 482 875 522 876 521 876 520 876 468 877 481 877 466 877 432 878 430 878 433 878 433 879 430 879 431 879 440 880 438 880 457 880 457 881 438 881 454 881 457 882 454 882 467 882 438 883 440 883 431 883 431 884 440 884 433 884 438 885 431 885 425 885 438 886 425 886 427 886 438 887 427 887 454 887 454 888 427 888 429 888 454 889 429 889 450 889 454 890 450 890 467 890 456 891 455 891 439 891 439 892 455 892 441 892 455 893 456 893 466 893 455 894 466 894 449 894 455 895 449 895 428 895 455 896 428 896 441 896 441 897 428 897 426 897 481 898 483 898 499 898 514 899 512 899 499 899 499 900 512 900 497 900 499 901 497 901 481 901 512 902 514 902 520 902 512 903 520 903 528 903 512 904 528 904 526 904 512 905 526 905 497 905 497 906 526 906 524 906 497 907 503 907 481 907 525 908 498 908 504 908 504 909 498 909 482 909 529 910 521 910 527 910 527 911 521 911 513 911 498 912 525 912 527 912 498 913 527 913 513 913 498 914 513 914 515 914 515 915 513 915 523 915 523 916 513 916 521 916 498 917 500 917 482 917 482 918 500 918 484 918 462 945 489 945 487 945 462 946 487 946 472 946 472 1062 463 1062 462 1062 463 1064 472 1064 464 1064 645 1104 450 1104 504 1104 504 1105 482 1105 645 1105 482 1106 467 1106 645 1106 467 1107 450 1107 645 1107 646 1108 452 1108 465 1108 489 1109 462 1109 646 1109 646 1110 506 1110 505 1110 646 1111 465 1111 474 1111 463 1112 464 1112 646 1112 447 1113 448 1113 646 1113 646 1114 492 1114 502 1114 646 1115 490 1115 492 1115 646 1116 502 1116 507 1116 646 1117 448 1117 452 1117 646 1118 507 1118 506 1118 446 1119 447 1119 646 1119 462 1120 463 1120 646 1120 501 1121 491 1121 646 1121 505 1122 501 1122 646 1122 451 1123 446 1123 646 1123 646 1124 480 1124 490 1124 646 1125 474 1125 480 1125 491 1126 489 1126 646 1126 464 1127 451 1127 646 1127 +

+
+
+ + +1 + + +
+
+ + + +7.481132 -6.50764 5.343665 +0 0 1 46.69194 +0 1 0 0.619768 +1 0 0 63.5593 +1 1 1 + + + +4.076245 1.005454 5.903862 +0 0 1 106.9363 +0 1 0 3.163707 +1 0 0 37.26105 +1 1 1 + + + +0 0 0 +0 0 1 0 +0 1 0 0 +1 0 0 90.00001 +1 1 1 + + + + + + + + + + + + + + +
diff --git a/ros/src/models/gazebo/vehicle_description/move_obstacles.jl b/ros/src/models/gazebo/vehicle_description/move_obstacles.jl index 46d4b0bf..73fee199 100755 --- a/ros/src/models/gazebo/vehicle_description/move_obstacles.jl +++ b/ros/src/models/gazebo/vehicle_description/move_obstacles.jl @@ -24,6 +24,7 @@ function loop(pub) end while !is_shutdown() + for i in 1:obs_num cmd = Twist() cmd.linear.x = RobotOS.get_param("/case/actual/obstacle/vx")[i] @@ -48,7 +49,7 @@ function main() pub = Array{Publisher{Twist}}(obs_num) for i in 1:obs_num - pub[i] = Publisher{Twist}(string("Obstacle",i,"/cmd_vel"), queue_size = 10) + pub[i] = Publisher{Twist}(string("Obstacle",i-1,"/cmd_vel"), queue_size = 10) end loop(pub) diff --git a/ros/src/models/gazebo/vehicle_description/scripts/spawn_obstacles.sh b/ros/src/models/gazebo/vehicle_description/scripts/spawn_obstacles.sh index 6d3d2c01..72ac9e8a 100755 --- a/ros/src/models/gazebo/vehicle_description/scripts/spawn_obstacles.sh +++ b/ros/src/models/gazebo/vehicle_description/scripts/spawn_obstacles.sh @@ -6,3 +6,4 @@ for ((idx=0; idx<$num_of_obstacles; idx++)) do roslaunch vehicle_description obstacles.launch case_params_path:=$case_params_path obstacle_idx:=$idx done +rosparam set system/vehicle_description/flags/obstacles_spawned true diff --git a/ros/src/models/gazebo/vehicle_description/src/frame_tf_broadcaster.cpp b/ros/src/models/gazebo/vehicle_description/src/frame_tf_broadcaster.cpp index 67a9c12f..4239e9a4 100644 --- a/ros/src/models/gazebo/vehicle_description/src/frame_tf_broadcaster.cpp +++ b/ros/src/models/gazebo/vehicle_description/src/frame_tf_broadcaster.cpp @@ -28,7 +28,7 @@ int main(int argc, char** argv){ double q2 = cy * cr * sp + sy * sr * cp; double q3 = sy * cr * cp - cy * sr * sp; */ - +// TODO get these parameters dynamically broadcaster1.sendTransform( tf::StampedTransform( tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.0, 0.0, 0.5)), @@ -37,7 +37,7 @@ int main(int argc, char** argv){ broadcaster2.sendTransform( tf::StampedTransform( tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(1.55, 0.0, 0.738)), - ros::Time::now(),"base_link", "velodyne_top_link")); + ros::Time::now(),"base_link", "lidar_frame")); r.sleep(); } } diff --git a/ros/src/models/gazebo/vehicle_description/urdf/hokuyo_laser.xacro b/ros/src/models/gazebo/vehicle_description/urdf/hokuyo_laser.xacro index 9d43ee9a..026394b1 100644 --- a/ros/src/models/gazebo/vehicle_description/urdf/hokuyo_laser.xacro +++ b/ros/src/models/gazebo/vehicle_description/urdf/hokuyo_laser.xacro @@ -1,17 +1,17 @@ - + - - + + - + - + @@ -22,7 +22,7 @@ - + @@ -37,15 +37,15 @@ - /bot + ${robotNamespace} gazebo_ros_control/DefaultRobotHWSim - /bot/control + /${robotNamespace}/control gazebo_control - + 0 0 0 0 0 0 false @@ -53,7 +53,7 @@ - 720 + 1875 1 -1.570796 1.570796 @@ -61,7 +61,7 @@ 0.10 - 30.0 + 100.0 0.01 @@ -75,8 +75,9 @@ - /rrbot/laser/scan - hokuyo_link + + ${lidar_topic} + ${lidar_frame} diff --git a/ros/src/models/gazebo/vehicle_description/urdf/mavs.urdf.xacro b/ros/src/models/gazebo/vehicle_description/urdf/mavs.urdf.xacro index e0eed01e..51be902a 100644 --- a/ros/src/models/gazebo/vehicle_description/urdf/mavs.urdf.xacro +++ b/ros/src/models/gazebo/vehicle_description/urdf/mavs.urdf.xacro @@ -19,6 +19,7 @@ + @@ -50,14 +51,21 @@ - + + + - - - + + + + + + + + diff --git a/ros/src/models/gazebo/vehicle_description/urdf/velodyne_16.xacro b/ros/src/models/gazebo/vehicle_description/urdf/velodyne_16.xacro index 0cb027e3..0372a34c 100644 --- a/ros/src/models/gazebo/vehicle_description/urdf/velodyne_16.xacro +++ b/ros/src/models/gazebo/vehicle_description/urdf/velodyne_16.xacro @@ -1,7 +1,7 @@ - + @@ -37,10 +37,10 @@ - + - + @@ -55,7 +55,7 @@ - + 0 0 0 0 0 0 false @@ -87,8 +87,8 @@ - ${topic} - /velodyne_top_link + ${lidar_topic} + /${lidar_frame} 0.9 130.0 0.008 diff --git a/ros/src/system/CMakeLists.txt b/ros/src/system/CMakeLists.txt index 18062c39..a86bf02e 100644 --- a/ros/src/system/CMakeLists.txt +++ b/ros/src/system/CMakeLists.txt @@ -4,16 +4,30 @@ project(system) find_package(catkin REQUIRED COMPONENTS roscpp rospy + std_msgs + mavs_msgs + nloptcontrol_planner ) catkin_metapackage() include_directories(${catkin_INCLUDE_DIRS}) +## Generate added messages and services with any dependencies listed here + generate_messages( + DEPENDENCIES + std_msgs + mavs_msgs + nloptcontrol_planner + ) + catkin_package( CATKIN_DEPENDS roscpp + rospy + std_msgs ) + add_executable(system_shutdown src/system_shutdown.cpp) target_link_libraries(system_shutdown ${catkin_LIBRARIES}) diff --git a/ros/src/system/README.md b/ros/src/system/README.md new file mode 100644 index 00000000..82653a8a --- /dev/null +++ b/ros/src/system/README.md @@ -0,0 +1,6 @@ +To load parameters from a yaml file into a running ros server: + +`rosparam load "path to yaml file"` + +Example: +`rosparam load $(rospack find system)/config/case/s5.yaml` diff --git a/ros/src/system/bootstrap.jl b/ros/src/system/bootstrap.jl index 0afa3ac4..7909b593 100755 --- a/ros/src/system/bootstrap.jl +++ b/ros/src/system/bootstrap.jl @@ -22,6 +22,12 @@ function main() println("waiting on move_obstacles.jl in vehicle_description ...") sleep(2) end + if RobotOS.has_param("system/vehicle_description/flags/obstacles_spawned") + while(!RobotOS.get_param("system/vehicle_description/flags/obstacles_spawned")) + println("waiting on creating obstacles in vehicle_description ...") + sleep(2) + end + end end end @@ -61,6 +67,15 @@ function main() end end + if RobotOS.has_param("system/result_store/flags/running") + if RobotOS.get_param("system/result_store/flags/running") + while(!RobotOS.get_param("system/result_store/flags/initialized")) + println("waiting on result store node to initialize in system ...") + sleep(5) + end + end + end + if RobotOS.has_param("system/sim_time/flags/running") if RobotOS.get_param("system/sim_time/flags/running") while(!RobotOS.get_param("system/sim_time/flags/initialized")) diff --git a/ros/src/system/config/case/s1.yaml b/ros/src/system/config/case/s1.yaml index e50975d0..ca1ad763 100644 --- a/ros/src/system/config/case/s1.yaml +++ b/ros/src/system/config/case/s1.yaml @@ -1,4 +1,5 @@ case: + id: Case1 goal: x: 0. yVal: 125. @@ -26,13 +27,13 @@ case: y0: [50] vx: [0] vy: [0] - + assumed: obstacle: num: 10 radius: [1.0,1.0,1.0,1.0,1.0,1.0,1.0,1.0,1.0,1.0] length: [4.0,4.0,4.0,4.0,4.0,4.0,4.0,4.0,4.0,4.0] x0: [-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0] - y0: [0,2,4,6,8,10,12,14,16,18] - vx: [0,0,0,0,0,0,0,0,0,0] - vy: [0,0,0,0,0,0,0,0,0,0] + y0: [0.,2.,4.,6.,8.,10.,12.,14.,16.,18.] + vx: [0.,0.,0.,0.,0.,0.,0.,0.,0.,0.] + vy: [0.,0.,0.,0.,0.,0.,0.,0.,0.,0.] diff --git a/ros/src/system/config/case/s3.yaml b/ros/src/system/config/case/s3.yaml index 3fafa3e9..d684164e 100644 --- a/ros/src/system/config/case/s3.yaml +++ b/ros/src/system/config/case/s3.yaml @@ -1,9 +1,10 @@ case: + id: Case2 goal: x: 0. yVal: 125. psi: 1.5701 - tol: 4 + tol: 15. actual: X0: @@ -33,6 +34,6 @@ case: radius: [1.0,1.0,1.0,1.0,1.0,1.0,1.0,1.0,1.0,1.0] length: [4.0,4.0,4.0,4.0,4.0,4.0,4.0,4.0,4.0,4.0] x0: [-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0] - y0: [0,2,4,6,8,10,12,14,16,18] - vx: [0,0,0,0,0,0,0,0,0,0] - vy: [0,0,0,0,0,0,0,0,0,0] + y0: [0.,2.,4.,6.,8.,10.,12.,14.,16.,18.] + vx: [0.,0.,0.,0.,0.,0.,0.,0.,0.,0.] + vy: [0.,0.,0.,0.,0.,0.,0.,0.,0.,0.] diff --git a/ros/src/system/config/case/s4.yaml b/ros/src/system/config/case/s4.yaml index 7e3eeeb8..88991c0b 100644 --- a/ros/src/system/config/case/s4.yaml +++ b/ros/src/system/config/case/s4.yaml @@ -1,13 +1,14 @@ case: + id: Case3 goal: - x: 200. + x: 0. yVal: 125. psi: 1.5701 tol: 15. actual: X0: - x: 200.0 + x: 0.0 yVal: 0.0 z: 0.5 v: 0.0 @@ -16,22 +17,23 @@ case: theta: 0.0 psi: 1.57079632679 sa: 0.0 - ux: 17.0 + ux: 0.0 ax: 0.0 obstacle: num: 3 radius: [5.,4.,2.] length: [5.,5.,5.] - x0: [205,180,200] - y0: [57,75,63] - vx: [-2,-1,-0.5] - vy: [0,1,6.] + x0: [5.,-20.,0.] + y0: [57.,75.,63.] + vx: [-2.,-1.,-0.5] + vy: [0.,1.,6.] + assumed: obstacle: num: 10 radius: [1.0,1.0,1.0,1.0,1.0,1.0,1.0,1.0,1.0,1.0] length: [4.0,4.0,4.0,4.0,4.0,4.0,4.0,4.0,4.0,4.0] x0: [-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0] - y0: [0,2,4,6,8,10,12,14,16,18] - vx: [0,0,0,0,0,0,0,0,0,0] - vy: [0,0,0,0,0,0,0,0,0,0] + y0: [0.,2.,4.,6.,8.,10.,12.,14.,16.,18.] + vx: [0.,0.,0.,0.,0.,0.,0.,0.,0.,0.] + vy: [0.,0.,0.,0.,0.,0.,0.,0.,0.,0.] diff --git a/ros/src/system/config/case/s5.yaml b/ros/src/system/config/case/s5.yaml new file mode 100644 index 00000000..c609b282 --- /dev/null +++ b/ros/src/system/config/case/s5.yaml @@ -0,0 +1,39 @@ +case: + id: Case5 + goal: + x: 0. + yVal: 200. + psi: 1.5701 + tol: 15. + + actual: + X0: + x: 0.0 + yVal: 0.0 + z: 0.5 + v: 0.0 + r: 0.0 + phi: 0.0 + theta: 0.0 + psi: 1.57079632679 + sa: 0.0 + ux: 0.0 + ax: 0.0 + obstacle: + num: 1 + radius: [10.] + length: [5.] + x0: [0.0] + y0: [150.] + vx: [0.0] + vy: [0.0] + + assumed: + obstacle: + num: 10 + radius: [1.0,1.0,1.0,1.0,1.0,1.0,1.0,1.0,1.0,1.0] + length: [4.0,4.0,4.0,4.0,4.0,4.0,4.0,4.0,4.0,4.0] + x0: [-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0] + y0: [0.,2.,4.,6.,8.,10.,12.,14.,16.,18.] + vx: [0.,0.,0.,0.,0.,0.,0.,0.,0.,0.] + vy: [0.,0.,0.,0.,0.,0.,0.,0.,0.,0.] diff --git a/ros/src/system/config/case/s6.yaml b/ros/src/system/config/case/s6.yaml new file mode 100644 index 00000000..865653e8 --- /dev/null +++ b/ros/src/system/config/case/s6.yaml @@ -0,0 +1,39 @@ +case: + id: Case6 + goal: + x: 0. + yVal: 200. + psi: 1.5701 + tol: 15. + + actual: + X0: + x: 0.0 + yVal: 0.0 + z: 0.5 + v: 0.0 + r: 0.0 + phi: 0.0 + theta: 0.0 + psi: 1.57079632679 + sa: 0.0 + ux: 0.0 + ax: 0.0 + obstacle: + num: 1 + radius: [10.] + length: [5.] + x0: [0.0] + y0: [250.] + vx: [0.0] + vy: [-3.0] + + assumed: + obstacle: + num: 10 + radius: [1.0,1.0,1.0,1.0,1.0,1.0,1.0,1.0,1.0,1.0] + length: [4.0,4.0,4.0,4.0,4.0,4.0,4.0,4.0,4.0,4.0] + x0: [-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0] + y0: [0.,2.,4.,6.,8.,10.,12.,14.,16.,18.] + vx: [0.,0.,0.,0.,0.,0.,0.,0.,0.,0.] + vy: [0.,0.,0.,0.,0.,0.,0.,0.,0.,0.] diff --git a/ros/src/system/config/case/s9.yaml b/ros/src/system/config/case/s9.yaml index 2b168e60..ec359913 100644 --- a/ros/src/system/config/case/s9.yaml +++ b/ros/src/system/config/case/s9.yaml @@ -1,4 +1,5 @@ case: + id: Case9 goal: x: 18. yVal: 700. @@ -26,13 +27,13 @@ case: y0: [281.,393.,0.,5.,10.,15.,20.,25.,30.,35.,40.,45.,50.,55.,60.,65.,70.,75.,80.,85.,90.,95.,100.,105.,110.,115.,120.,125.,130.,135.,140.,145.,150.,155.,160.,165.,170.,175.] vx: [0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0] vy: [0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0] - + assumed: obstacle: num: 10 radius: [1.0,1.0,1.0,1.0,1.0,1.0,1.0,1.0,1.0,1.0] length: [4.0,4.0,4.0,4.0,4.0,4.0,4.0,4.0,4.0,4.0] x0: [-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0,-100.0] - y0: [0,2,4,6,8,10,12,14,16,18] - vx: [0,0,0,0,0,0,0,0,0,0] - vy: [0,0,0,0,0,0,0,0,0,0] + y0: [0.,2.,4.,6.,8.,10.,12.,14.,16.,18.] + vx: [0.,0.,0.,0.,0.,0.,0.,0.,0.,0.] + vy: [0.,0.,0.,0.,0.,0.,0.,0.,0.,0.] diff --git a/ros/src/system/config/detection/obstacle_detector.yaml b/ros/src/system/config/detection/obstacle_detector_pcl.yaml similarity index 62% rename from ros/src/system/config/detection/obstacle_detector.yaml rename to ros/src/system/config/detection/obstacle_detector_pcl.yaml index 3fe38dcc..dce889bc 100644 --- a/ros/src/system/config/detection/obstacle_detector.yaml +++ b/ros/src/system/config/detection/obstacle_detector_pcl.yaml @@ -1,24 +1,28 @@ obstacle_detector: obstacle_extractor: - active: 'true' - use_pcl: 'true' - use_scan: 'false' - use_split_and_merge: 'true' - circles_from_visibles: 'true' - discard_converted_segments: 'false' - transform_coordinates: 'true' + active: true + use_pcl: true + use_scan: false + use_split_and_merge: true + circles_from_visibles: true + discard_converted_segments: false + transform_coordinates: true min_group_points: 5 max_group_distance: 0.5 distance_proportion: 0.001 max_split_distance: 5 max_merge_separation: 3 max_merge_spread: 2 - max_circle_radius: 4 + max_circle_radius: 15 radius_enlargement: 0.3 frame_id: 'map' + p_min_x_limit: -1000. + p_max_x_limit: 1000. + p_min_y_limit: -1000. + p_max_y_limit: 1000. obstacle_tracker: - active: 'true' + active: true loop_rate: 100.0 tracking_duration: 1 min_correspondence_cost: 0.6 @@ -32,5 +36,5 @@ voxel_grid: filter_field_name: 'z' filter_limit_min: 0.01 filter_limit_max: 3.5 - filter_limit_negative: 'false' + filter_limit_negative: false leaf_size: 0.01 diff --git a/ros/src/system/config/detection/obstacle_detector_scan.yaml b/ros/src/system/config/detection/obstacle_detector_scan.yaml new file mode 100644 index 00000000..d2d98cde --- /dev/null +++ b/ros/src/system/config/detection/obstacle_detector_scan.yaml @@ -0,0 +1,33 @@ +obstacle_detector: + obstacle_extractor: + active: true + use_pcl: false + use_scan: true + use_split_and_merge: true + circles_from_visibles: false + discard_converted_segments: false + transform_coordinates: true + min_group_points: 5 + max_group_distance: 0.5 + distance_proportion: 0.001 + max_split_distance: 5 + max_merge_separation: 3 + max_merge_spread: 2 + max_circle_radius: 15 + radius_enlargement: 0.3 + frame_id: 'map' + p_min_x_limit: -1000. + p_max_x_limit: 1000. + p_min_y_limit: -1000. + p_max_y_limit: 1000. + + obstacle_tracker: + active: true + loop_rate: 100.0 + tracking_duration: 1 + min_correspondence_cost: 0.6 + std_correspondence_dev: 0.15 + process_variance: 0.1 + process_rate_variance: 0.1 + measurement_variance: 1.0 + frame_id: 'map' diff --git a/ros/src/system/config/planner/nloptcontrol_planner/default.yaml b/ros/src/system/config/planner/nloptcontrol_planner/default.yaml index 44ed40e7..80a243f4 100644 --- a/ros/src/system/config/planner/nloptcontrol_planner/default.yaml +++ b/ros/src/system/config/planner/nloptcontrol_planner/default.yaml @@ -35,7 +35,7 @@ planner: xFslackVariables: true movingObstacles: true onlyOptimal: false - evalConstraints: true + evalConstraints: false ocpSave: true weights: diff --git a/ros/src/system/config/planner/nloptcontrol_planner/new.yaml b/ros/src/system/config/planner/nloptcontrol_planner/new.yaml new file mode 100644 index 00000000..f0baf5e3 --- /dev/null +++ b/ros/src/system/config/planner/nloptcontrol_planner/new.yaml @@ -0,0 +1,119 @@ +planner: + nloptcontrol_planner: + misc: + mode: OCP + IPplant: ThreeDOFv1 + model: ThreeDOFv2 # function name + Xlims: NaN # N/A plotting limit for x + Ylims: NaN # N/A plotting limit for y + Xmin: NaN # min limit for x in OCP + Xmax: NaN # max limit for x in OCP + Ymin: NaN # min limit for y in OCP + Ymax: NaN # max limit for y in OCP + tp: NaN # N/A prediction horizon (s) + tex: 0.5 # execution horizon (s) + sm: 2. # (m) distance to see if obstacle was hit (for crash checking) + sm1: 2.5 # (m) distance 1 to make sure we don't hit obstacle (for optimization) + sm2: 4.0 # (m) distance 2 to make sure we don't hit obstacle (for optimization) + Lr: 90. # LiDAR range (m) + L_rd: 10. # relaxation distance to LiDAR range + Nck: NaN # number of points per interval + N: 20 # number of points in :tm methods + solver: Ipopt # either Ipopt of KNITRO + mpc_max_iter: 1000 # an MPC parameter + PredictX0: false # if the state that the vehicle will be at when the optimization is finished is to be predicted + FixedTp: true # fixed final time for predicting X0 + finalTimeDV: true # bool to indicate if the final time is a variable + activeSafety: NaN # a bool if the system is only used to avoid collisions with obstacles + followDriver: NaN # a bool to try and follow the driver + followPath: NaN # a bool to follow the path + NF: NaN # number to subtract off the constraint check vector-> used for activeSafety mode so driver sees obstacle before autonomy + integrationScheme: trapezoidal + tfMax: 20.0 # maximum final time in MPC + EP: 0.01 # small number to avoid singularities TODO move this from VehicleModels.jl + x0slackVariables: true + xFslackVariables: true + movingObstacles: false + onlyOptimal: true + evalConstraints: false + ocpSave: false + + weights: + ic: 100.0 + x0: 50. #0.1 + y0: 50. #0.1 + v0: 10.0 #10. + r0: 10.0 #10. + psi0: 10.0 #1. + sa0: 2. #2. + ux0: 0.1 #0.1 + ax0: 0.1 #0.1 + xf: 100. + goal: 10. # 100. + psi: 0.01 + time: 50. + haf: 1. + Fz: 0.5 # 0.1 + ce: 1. + sa: 0.1 + sr: 1. + ax: 0.1 + jx: 0.01 + path: 1.0 + driver: 1.0 + + tolerances: + ix: 10.0 # 0.5 #0.05 + iy: 10.0 #0.5 #0.05 + iv: 10.0 # 0.5 #0.05 + ir: 10.0 # 0.05 #0.15 + ipsi: 10.0 #0.5 #0.07 + isa: 10.0 #0.025 #0.0025 + iu: 1.0 #0.5 #0.25 + iax: 10.0 #0.5 # 0.05 + fx: 10.0 #5.0 # 5.0 + fy: 10.0 #5.0 # 5.0 + fv: NaN # NOTE YAML file turns these into strings + fr: NaN + fpsi: NaN + fsa: NaN + fu: NaN + fax: NaN + + solver: + # settings for both KNITRO and IPOPT + outlev: 0 # (c.m.solver==:Ipopt) ? :print_level : :outlev # print level + feastol_abs: 7e-1 #7e-2 # (c.m.solver==:Ipopt) ? :constr_viol_tol : :feastol_abs + maxit: 500 # (c.m.solver==:Ipopt) ? :max_iter : :maxit + maxtime_cpu: 30. # (c.m.solver==:Ipopt) ? :max_cpu_time : :maxtime_cpu + + # settings for KNITRO + ftol: 1e-15 # relative change in the objective function is less than ftol for ftol_iters consecutive iterations + feastol: 1.0e20 # relative stopping tolerance for the feasibility error + ftol_iters: 5 # number of iters to stop after if change in obj fun is less than + infeastol: 1e-2 # (relative) tolerance used for declaring infeasibility of a model + maxfevals: -1 # maximum number of function evaluations before termination + maxtime_real: 30. # in seconds, the maximum allowable real time before termination + opttol: 1e20 # final relative stopping tolerance for the KKT (optimality) error + opttol_abs: 5e-1 # final absolute stopping tolerance for the KKT (optimality) error + xtol: 1e-12 # optimization process will terminate if the relative change in all components of the solution point estimate is less than xtol for xtol_iters + algorithm: 1 + bar_murule: 1 + linsolver: 4 + cg_pmem: 0 + bar_initpt: 3 + bar_penaltycons: 1 + bar_penaltyrule: 2 + bar_switchrule: 2 + linesearch: 1 + + # settings for Ipopt + warm_start_init_point: yes # + dual_inf_tol: 5. # Absolute tolerance on the dual infeasibility + compl_inf_tol: 1e-1 # Absolute tolerance on the complementarity. + acceptable_tol: 1e-2 # Determines which (scaled) overall optimality error is considered to be "acceptable. + acceptable_constr_viol_tol: 0.01 # Absolute tolerance on the constraint violation. "Acceptable" termination requires that the max-norm of the (unscaled) constraint violation is less than this threshold + acceptable_dual_inf_tol: 1e10 # Acceptable" termination requires that the (max-norm of the unscaled) dual infeasibility is less than this threshold + acceptable_compl_inf_tol: 0.01 # "Acceptable" termination requires that the max-norm of the (unscaled) complementarity is less than this threshold + acceptable_obj_change_tol: 1e20 # If the relative change of the objective function (scaled by Max(1,|f(x)|)) is less than this value, this part of the acceptable tolerance termination is satisfied + diverging_iterates_tol: 1e20 diff --git a/ros/src/system/config/planner/nloptcontrol_planner/plannerA.yaml b/ros/src/system/config/planner/nloptcontrol_planner/plannerA.yaml index e5de23cc..bd272d20 100644 --- a/ros/src/system/config/planner/nloptcontrol_planner/plannerA.yaml +++ b/ros/src/system/config/planner/nloptcontrol_planner/plannerA.yaml @@ -34,9 +34,9 @@ planner: x0slackVariables: true xFslackVariables: true movingObstacles: false - onlyOptimal: false - evalConstraints: true - ocpSave: true + onlyOptimal: true + evalConstraints: false + ocpSave: false weights: ic: 100.0 diff --git a/ros/src/system/config/planner/nloptcontrol_planner/plannerB.yaml b/ros/src/system/config/planner/nloptcontrol_planner/plannerB.yaml index d8724726..79c09584 100644 --- a/ros/src/system/config/planner/nloptcontrol_planner/plannerB.yaml +++ b/ros/src/system/config/planner/nloptcontrol_planner/plannerB.yaml @@ -34,9 +34,9 @@ planner: x0slackVariables: true xFslackVariables: true movingObstacles: false - onlyOptimal: false - evalConstraints: true - ocpSave: true + onlyOptimal: true + evalConstraints: false + ocpSave: false weights: ic: 100.0 diff --git a/ros/src/system/config/planner/nloptcontrol_planner/plannerC.yaml b/ros/src/system/config/planner/nloptcontrol_planner/plannerC.yaml index 1dc9be5c..83545756 100644 --- a/ros/src/system/config/planner/nloptcontrol_planner/plannerC.yaml +++ b/ros/src/system/config/planner/nloptcontrol_planner/plannerC.yaml @@ -34,9 +34,10 @@ planner: x0slackVariables: true xFslackVariables: true movingObstacles: false - onlyOptimal: false - evalConstraints: true - ocpSave: true + onlyOptimal: true + evalConstraints: false + ocpSave: false + weights: ic: 100.0 diff --git a/ros/src/system/config/planner/nloptcontrol_planner/plannerD.yaml b/ros/src/system/config/planner/nloptcontrol_planner/plannerD.yaml index 44ed40e7..618bd7aa 100644 --- a/ros/src/system/config/planner/nloptcontrol_planner/plannerD.yaml +++ b/ros/src/system/config/planner/nloptcontrol_planner/plannerD.yaml @@ -34,9 +34,9 @@ planner: x0slackVariables: true xFslackVariables: true movingObstacles: true - onlyOptimal: false - evalConstraints: true - ocpSave: true + onlyOptimal: true + evalConstraints: false + ocpSave: false weights: ic: 100.0 diff --git a/ros/src/system/config/system/demos/demoA.yaml b/ros/src/system/config/system/demos/demoA.yaml index e7e14a00..954fdc8f 100644 --- a/ros/src/system/config/system/demos/demoA.yaml +++ b/ros/src/system/config/system/demos/demoA.yaml @@ -7,7 +7,7 @@ system: flags: initialized: false paused: true - + shutdown: flags: running: true @@ -22,9 +22,10 @@ system: running: true lidar_initialized: false obstacles_initialized: false + obstacles_spawned: false postion_update_external: false params: - step_distance: 0.5 + step_distance: 0.0 obstacle_detector: flags: diff --git a/ros/src/system/config/system/demos/demoB.yaml b/ros/src/system/config/system/demos/demoB.yaml index 2f13be40..0757c9f5 100644 --- a/ros/src/system/config/system/demos/demoB.yaml +++ b/ros/src/system/config/system/demos/demoB.yaml @@ -20,6 +20,7 @@ system: running: true lidar_initialized: false obstacles_initialized: false + obstacles_spawned: false postion_update_external: true nloptcontrol_planner: diff --git a/ros/src/system/config/system/demos/demoI.yaml b/ros/src/system/config/system/demos/demoI.yaml index 073fbfae..97947af5 100644 --- a/ros/src/system/config/system/demos/demoI.yaml +++ b/ros/src/system/config/system/demos/demoI.yaml @@ -3,9 +3,9 @@ system: plant: chrono params: - step_size: 0.01 + step_size: 0.005 goal_tol: 0.1 - tire_step_size: 0.005 + tire_step_size: 0.00025 flags: goal_attained: false @@ -43,6 +43,7 @@ system: running: true lidar_initialized: false obstacles_initialized: false + obstacles_spawned: false postion_update_external: true sim_time: diff --git a/ros/src/system/config/system/demos/demoK.yaml b/ros/src/system/config/system/demos/demoK.yaml index 12dd115f..acaa980b 100644 --- a/ros/src/system/config/system/demos/demoK.yaml +++ b/ros/src/system/config/system/demos/demoK.yaml @@ -3,9 +3,9 @@ system: plant: chrono params: - step_size: 0.01 + step_size: 0.005 goal_tol: 0.1 - tire_step_size: 0.005 + tire_step_size: 0.00025 flags: goal_attained: false @@ -43,6 +43,7 @@ system: running: true lidar_initialized: false obstacles_initialized: false + obstacles_spawned: false postion_update_external: true sim_time: @@ -52,4 +53,3 @@ system: control_initial_size: 2 receive_flag: false - diff --git a/ros/src/system/config/system/demos/demoM.yaml b/ros/src/system/config/system/demos/demoM.yaml index 78364807..5297d71b 100644 --- a/ros/src/system/config/system/demos/demoM.yaml +++ b/ros/src/system/config/system/demos/demoM.yaml @@ -3,9 +3,9 @@ system: plant: chrono params: - step_size: 0.01 + step_size: 0.005 goal_tol: 0.1 - tire_step_size: 0.005 + tire_step_size: 0.00025 flags: goal_attained: false @@ -35,21 +35,22 @@ system: gui: true field: h: 0 - l: 500.0 - w: 500.0 + l: 1000.0 + w: 1000.0 vehicle_description: flags: running: true lidar_initialized: false obstacles_initialized: false + obstacles_spawned: false postion_update_external: true obstacle_detector: flags: running: true initialized: false - + sim_time: flags: initialized: false diff --git a/ros/src/system/config/system/demos/demoZ.yaml b/ros/src/system/config/system/demos/demoZ.yaml new file mode 100644 index 00000000..659b3ce3 --- /dev/null +++ b/ros/src/system/config/system/demos/demoZ.yaml @@ -0,0 +1,63 @@ +system: + planner: nlopcontrol_planner + plant: chrono + + params: + step_size: 0.005 + goal_tol: 0.1 + tire_step_size: 0.00025 + + flags: + goal_attained: false + initialized: false + paused: true + + result_store: + flags: + running: true + initialized: false + shutdown: false + + shutdown: + flags: + running: true + initialized: false + params: + shutdown_initiation_flags: ["result_store/flags/shutdown"] + shutdown_completion_flags: [] + + nloptcontrol_planner: + namespace: nlopcontrol_planner + flags: + running: true + initialized: false + known_environment: false + + chrono: + namespace: chrono + flags: + initialized: false + running: true + gui: true + field: + h: 0 + l: 1000.0 + w: 1000.0 + + vehicle_description: + flags: + running: true + lidar_initialized: false + obstacles_initialized: false + obstacles_spawned: false + postion_update_external: true + + obstacle_detector: + flags: + running: true + initialized: false + + sim_time: + flags: + initialized: false + running: true diff --git a/ros/src/system/config/system/pkgs/vehicle_description.yaml b/ros/src/system/config/system/pkgs/vehicle_description.yaml index 0d6ec6fa..e1fc0220 100644 --- a/ros/src/system/config/system/pkgs/vehicle_description.yaml +++ b/ros/src/system/config/system/pkgs/vehicle_description.yaml @@ -9,4 +9,4 @@ system: obstacles_initialized: false postion_update_external: false params: - step_distance: 0.5 + step_distance: 0.0 diff --git a/ros/src/system/config/system/result_model.json b/ros/src/system/config/system/result_model.json new file mode 100644 index 00000000..a1daf5c5 --- /dev/null +++ b/ros/src/system/config/system/result_model.json @@ -0,0 +1,60 @@ +{ + "model_id": "model1", + "add_description": true, + "description_header": "Description", + "default_description": "Shutdown was caused by some unmonitored external phenomenon.", + "model": [ + { + "key": "Case Id", + "val": "/case/id", + "ros_msg_type": "parameter", + "save": true + }, + { + "key": "Vehicle Collided", + "val": "/vehicle_collided", + "ros_msg_type": "parameter", + "save": true, + "stopping_criteria": { + "logical_op": "OR", + "conditions": [ + { + "op": "eq", + "val": true + } + ], + "description": "Vehicle has collided." + } + }, + { + "key": "Goal attained", + "val": "/system/flags/goal_attained", + "ros_msg_type": "parameter", + "save": true, + "stopping_criteria": { + "logical_op": "OR", + "conditions": [ + { + "op": "eq", + "val": true + } + ], + "description": "Goal is attained." + } + }, + { + "key": "Steering Angle", + "val": "/state", + "sub_val": "sa", + "ros_msg_type": "topic", + "dataType": "state", + "save": true + }, + { + "key": "Asumed obstacle X coord", + "val": "/case/assumed/obstacle/x0", + "ros_msg_type": "parameter", + "save": true + } + ] +} diff --git a/ros/src/system/config/vehicle/hmmwv.yaml b/ros/src/system/config/vehicle/hmmwv.yaml index 2694050a..2839b959 100644 --- a/ros/src/system/config/vehicle/hmmwv.yaml +++ b/ros/src/system/config/vehicle/hmmwv.yaml @@ -10,6 +10,9 @@ vehicle: robotName: hmmwv # NOTE cannot change, will break vehicle.launch because this is hardcoded in frameName: map ground_truth_topic: base_pose_ground_truth + lidar_model: 2 # 1: velodyne VLP16; 2: hokuyo_laser + lidar_frame: lidar_frame # NOTE cannot change until frame_tf_broadcaster.cpp does not hardcode in the lidar_frame!! + lidar_topic: scan # mesh parameters scale_factor: 0.2 diff --git a/ros/src/system/launch/demoA.launch b/ros/src/system/launch/demoA.launch index 04725a66..db8aac5d 100644 --- a/ros/src/system/launch/demoA.launch +++ b/ros/src/system/launch/demoA.launch @@ -3,14 +3,13 @@ - - + - + @@ -27,13 +26,10 @@ - - - - - - - + + + + diff --git a/ros/src/system/launch/demoI.launch b/ros/src/system/launch/demoI.launch index 4c58602b..b9f66b94 100644 --- a/ros/src/system/launch/demoI.launch +++ b/ros/src/system/launch/demoI.launch @@ -6,13 +6,13 @@ - + - + @@ -22,7 +22,7 @@ - + @@ -65,7 +65,8 @@ + /state + /control"/> diff --git a/ros/src/system/launch/demoK.launch b/ros/src/system/launch/demoK.launch index c3a40d66..b258d0d3 100644 --- a/ros/src/system/launch/demoK.launch +++ b/ros/src/system/launch/demoK.launch @@ -6,13 +6,13 @@ - + - + @@ -22,12 +22,10 @@ - - + - @@ -42,7 +40,6 @@ - @@ -67,10 +64,11 @@ - + /state + /control"/> diff --git a/ros/src/system/launch/demoM.launch b/ros/src/system/launch/demoM.launch index 9ee69e0b..06c7d5e2 100644 --- a/ros/src/system/launch/demoM.launch +++ b/ros/src/system/launch/demoM.launch @@ -6,15 +6,11 @@ - + - - - - @@ -24,7 +20,8 @@ - + + @@ -44,13 +41,7 @@ - - - - - - - + @@ -76,10 +67,11 @@ - + /state + /control"/> diff --git a/ros/src/system/launch/demoZ.launch b/ros/src/system/launch/demoZ.launch new file mode 100644 index 00000000..0f24b856 --- /dev/null +++ b/ros/src/system/launch/demoZ.launch @@ -0,0 +1,85 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + results_file: /home/mavs/MAVs/results/report.csv + model_filename_path: $(find system)/config/system/result_model.json + + + + + + + + + + + + + + + diff --git a/ros/src/system/package.xml b/ros/src/system/package.xml index 7c64b1a3..64ab8b90 100644 --- a/ros/src/system/package.xml +++ b/ros/src/system/package.xml @@ -17,21 +17,24 @@ catkin - + roscpp rospy - rostest + rostest genmsg std_msgs + mavs_msgs + nloptcontrol_planner - nloptcontrol_planner vehicle_description obstacle_detector ros_base_planner + + diff --git a/ros/src/system/scripts/result_store.py b/ros/src/system/scripts/result_store.py new file mode 100755 index 00000000..db893428 --- /dev/null +++ b/ros/src/system/scripts/result_store.py @@ -0,0 +1,247 @@ +#!/usr/bin/env python +import numpy as np +import rospy +import json +import csv +from std_msgs.msg import String, Float64, Int64, Bool +from mavs_msgs.msg import state, control +from nloptcontrol_planner.msg import Trajectory + +def do_shutdown_preprocess(): + record_data_row() + close_file() + +def set_ros_param_shutdown_flag(): + rospy.set_param("result_store/flags/shutdown", True) + +def get_csv_file_writer(file_path): + global csv_file + global csv_writer + try: + fh = open(file_path, 'r') + fh.close() + csv_file = open(file_path, 'a+') # create a new handle in append mode and return + csv_writer = csv.writer(csv_file, delimiter=',', quotechar='|', quoting=csv.QUOTE_MINIMAL) + + except Exception: + # create a new file, add header and return get_file_handle + csv_file = open(file_path, 'w+') + csv_writer = csv.writer(csv_file, delimiter=',', quotechar='|', quoting=csv.QUOTE_MINIMAL) + add_file_headers() + +def add_file_headers(): + global model + global csv_writer + headers = [] + for obj in model["model"]: + if "save" in obj and obj["save"] == True: + k = "PLEASE_PROVIDE_KEY" + if "key" in obj: + k = obj["key"] + headers.append(k) + if model["add_description"] == True: + d_header = "Description" + if "description_header" in model: + d_header = model["description_header"] + headers.append(d_header) + csv_writer.writerow(headers) + +def close_file(): + global csv_file + try: + csv_file.close() + except Exception: + pass + +def record_data_row(): + global model + global csv_writer + row=[] + desc = "" + for obj in model["model"]: + if "save" in obj and obj["save"] == True: + row.append(obj["__VAL__"]) + if obj["__CAUSED_SHUTDOWN__"] == True: + if "description" in obj["stopping_criteria"]: + desc = desc + obj["stopping_criteria"]["description"] + if model["add_description"] == True: + if len(desc) == 0 and "default_description" in model: + desc = model["default_description"] + row.append(desc) + csv_writer.writerow(row) + +def check_if_object_causes_shutdown(key): + global shutdown_flag + global model + global key_map + caused_shutdown = False + ob = model["model"][key_map[key]] + if not ("stopping_criteria" in ob) or not ("conditions" in ob["stopping_criteria"]): + return False + else: + conditons = ob["stopping_criteria"]["conditions"] + op = "None" + if "logical_op" in ob["stopping_criteria"]: + op = ob["stopping_criteria"]["logical_op"] + caused_shutdown = evaluate_shutdown_conditions_for_object(ob["__VAL__"], conditons, op) + model["model"][key_map[key]]["__CAUSED_SHUTDOWN__"] = caused_shutdown + return caused_shutdown + +def evaluate_shutdown_conditions_for_object(val, conditions, logical_op="None"): + #default logical connector for conditions + if logical_op is None: + logical_op = "OR" + logical_op = logical_op.upper() + if logical_op == "AND": + shutdown_criteria_met = True and len(conditions) > 0 + for c in conditions: + shutdown_criteria_met = shutdown_criteria_met and eval_single_condition(val, c, logical_op) + if shutdown_criteria_met == False: + break + return shutdown_criteria_met + else: + shutdown_criteria_met = False + for c in conditions: + shutdown_criteria_met = shutdown_criteria_met or eval_single_shutdown_condition(val, c, logical_op) + if shutdown_criteria_met == True: + break + return shutdown_criteria_met + +def eval_single_shutdown_condition(val, condition, logical_op): + conditional_op = condition["op"] + target = condition["val"] + if not isinstance(val, list): + return check_single_conditional_equality(val, target, conditional_op) + else: # if value is a list then all element should satisfy conditions + if logical_op == "AND": + shutdown_criteria_met = True + for v in val: + shutdown_criteria_met = shutdown_criteria_met and check_single_conditional_equality(v, target, conditional_op) + if shutdown_criteria_met == False: + break + return shutdown_criteria_met + else: + shutdown_criteria_met = False + for v in val: + shutdown_criteria_met = shutdown_criteria_met or check_single_conditional_equality(v, target, conditional_op) + if shutdown_criteria_met == True: + break + return shutdown_criteria_met + +def check_single_conditional_equality(val, target, conditional_op): + conditional_op = conditional_op.lower() + if conditional_op == "lt": + return val < target + elif conditional_op == "lte": + return val <= target + elif conditional_op == "gt": + return val > target + elif conditional_op == "gte": + return val >= target + elif conditional_op == "eq": + return val == target + elif conditional_op == "neq": + return val != target + + +def add_dataval_and_caused_shutdown_variable_in_model_objects(): + global model + for obj in model["model"]: + obj["__VAL__"] = None + obj["__CAUSED_SHUTDOWN__"] = False + +# store a map of index of each object to save +def update_key_map(): + global key_map + global model + for i in range(len(model["model"])): + key_map[model["model"][i]["key"]] = i + +def update_object_val(msg, args): + global model + global key_map + global shutdown_flag + if shutdown_flag == False: + key = args[0] + sub_val = args[1] + val = msg + if sub_val is not None: + child_arr = sub_val.split("/") + for ch in child_arr: + val=getattr(val, ch) + model["model"][key_map[key]]["__VAL__"] = val + shutdown_flag = check_if_object_causes_shutdown(key) + +def update_ros_parameters_in_model(): + global model + for obj in model["model"]: + if obj["ros_msg_type"].lower() == "parameter": + key = obj["key"] + if rospy.has_param(obj["val"]): + val = rospy.get_param(obj["val"]) + update_object_val(val, (key, None)) + +def subscribe_to_topics_in_model(): + global model + global subscribers + for obj in model["model"]: + if obj["ros_msg_type"].lower() == "topic": + _key = obj["key"] + topic_name = obj["val"] + sub_val = None + if "sub_val" in obj: + sub_val = obj["sub_val"] + _dtype = obj["dataType"] + if _dtype == "Bool": + sub = rospy.Subscriber(topic_name, Bool, update_object_val, (_key, None)) + elif _dtype == "String": + sub = rospy.Subscriber(topic_name, String, update_object_val, (_key, None)) + elif _dtype == "Int64": + sub = rospy.Subscriber(topic_name, Int64, update_object_val, (_key, None)) + elif _dtype == "Float64": + sub = rospy.Subscriber(topic_name, Float64, update_object_val, (_key, None)) + elif _dtype == "state": + sub = rospy.Subscriber(topic_name, state, update_object_val, (_key, sub_val)) + elif _dtype == "control": + sub = rospy.Subscriber(topic_name, control, update_object_val, (_key, sub_val)) + elif _dtype == "Trajectory": + sub = rospy.Subscriber(topic_name, Trajectory, update_object_val, (_key, sub_val)) + subscribers.append(sub) + +def update_shutdown_flag_for_future_enhancements(): + # In future you can call your own functions here to set the global shutdown_flag + # It will automatically trigger shutdown with parameter saving + pass + +if __name__ == '__main__': + rospy.init_node("result_store") + csv_file = "" + csv_writer = None + model = {} + key_map = {} + shutdown_flag = False + subscribers=[] + + file_path = rospy.get_param("/result_store/results_file") + model_path = rospy.get_param("/result_store/model_filename_path") + # load data model to save + with open(model_path) as f: + model = json.load(f) + update_key_map() + get_csv_file_writer(file_path) + + # Add a __VAL__ and __CAUSED_SHUTDOWN__ to all model objects + add_dataval_and_caused_shutdown_variable_in_model_objects() + + # subscribe to topics in a loop and update them with new data continuously + subscribe_to_topics_in_model() + # Set shutdown callback for saving file, etc + rospy.on_shutdown(do_shutdown_preprocess) + rospy.set_param("system/result_store/flags/initialized", True) + rate = rospy.Rate(10) # 50hz + while not rospy.is_shutdown() and not shutdown_flag: + update_ros_parameters_in_model() + update_shutdown_flag_for_future_enhancements() + rate.sleep() + if shutdown_flag == True: + set_ros_param_shutdown_flag() diff --git a/ros/src/system/src/system_shutdown.cpp b/ros/src/system/src/system_shutdown.cpp index 413d1139..4728d7a4 100644 --- a/ros/src/system/src/system_shutdown.cpp +++ b/ros/src/system/src/system_shutdown.cpp @@ -71,11 +71,12 @@ void checkForShutdownRequest() { bool initiate_shutdown; ros::param::get(shutdown_initiation_flags[i], initiate_shutdown); if (initiate_shutdown) { + ROS_INFO("Shutdown initiation flag triggered!!!! = %s\n", shutdown_initiation_flags[i].c_str()); g_request_shutdown = 1; break; } } else { - // for debug purposes + // for debug purposes // ROS_WARN("Following parameter is expected for shutdown initiation but not found: %s.\n", shutdown_initiation_flags[i].c_str()); } }