Skip to content

Commit

Permalink
Merge remote-tracking branch 'upstream/main' into main
Browse files Browse the repository at this point in the history
  • Loading branch information
anchobi-no committed Jan 5, 2021
2 parents f13ae0f + cb164d9 commit 2985085
Show file tree
Hide file tree
Showing 10 changed files with 280 additions and 47 deletions.
29 changes: 8 additions & 21 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -291,7 +291,11 @@ rqt, joystick, 各種コントローラーで車両操作し、学習用のデ

```
cd ~/catkin_ws/src/ai_race/ai_race/utility/scripts
python keyboard_con_pygame2.py
python keyboard_con_pygame_videosave.py
### `ESC`キー押下で終了
### 終了後、学習データ(画像とコマンド)を格納したディレクトリがあることをコマンドから確認する
ls ${HOME}/Images_from_rosbag/
```

上記実行後、左下の「?」のうち`keyboard_con....py`が表示されてるものを押して、<br>
Expand All @@ -304,26 +308,9 @@ a 左にまがる
d 右にまがる
```

車両が動いている際の、画像とコマンド操作ログを取得するには以下を別ターミナルで実行します。<br>
デフォルトでは`${HOME}`に画像とコマンド操作ログを含む`rosbag(.bag)`ファイルが出力されます。<br>

```
roslaunch sim_environment rosbag.launch
### `Ctl+C`で終了する
### 終了後、rosbag(.bag)ファイルがあることをコマンドから確認する
ls ${HOME}/*.bag
```

`rosbag(.bag)`ファイルを、画像とコマンドに変換するには以下を実行します。<br>
デフォルトでは`${HOME}/Images_from_rosbag/.`以下にファイルが出力されます。<br>

```
cd ~/catkin_ws/src/ai_race/ai_race/utility/script
python rosbag_to_images_and_commands.py xxx.bag # xxx.bagファイルは実在するrosbagファイルを指定する
ls ${HOME}/Images_from_rosbag/. # 画像とコマンドの変換データがあること確認する
```

`keyboard_con_pygame_videosave.py`の停止は`ESC`キーを押下して下さい。<br>
その後、`${HOME}/Images_from_rosbag/`以下に学習データ(画像とコマンド)が格納されます。<br>
<br>
以上で作成したデータを、学習モデル作成に使用下さい。

### 3.2. 各種コマンドの説明
Expand Down
6 changes: 6 additions & 0 deletions ai_race/learning/launch/inference_from_image.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,15 @@
<launch>
<!-- roslaunch arguments -->
<arg name="trt_model" default="default_path" />
<arg name="image_topic_name" default="/front_camera/image_exp" />

<!-- republish raw image -->
<include file="$(find sim_environment)/launch/image_republish.launch"/>

<!-- call node -->
<node pkg="learning" type="rosnode_inference_from_image.py" name="rosnode_inference_from_image" output="screen" >
<param name="trt_model" value="$(arg trt_model)" />
<param name="image_topic_name" value="$(arg image_topic_name)" />
</node>

</launch>
5 changes: 2 additions & 3 deletions ai_race/learning/scripts/MyDataSet.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,9 +9,8 @@
IMG_IDX = 1

class MyDataset(Dataset):
def __init__(self, csv_file_path, root_dir, transform=None):
self.image_dataframe = pd.read_csv(csv_file_path,engine='python')
self.root_dir = root_dir
def __init__(self,image_dataframe, transform=None):
self.image_dataframe = image_dataframe
self.transform = transform

def __len__(self):
Expand Down
4 changes: 3 additions & 1 deletion ai_race/learning/scripts/inference_from_image.py
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,8 @@ def inference_from_image():
global twist_pub
rospy.init_node('inference_from_image', anonymous=True)
twist_pub = rospy.Publisher('/cmd_vel', Twist, queue_size=1)
rospy.Subscriber("/front_camera/image_raw", Image, set_throttle_steer)
image_topic_name = args.image_topic_name
rospy.Subscriber(image_topic_name, Image, set_throttle_steer)
r = rospy.Rate(10)
#while not rospy.is_shutdown():
# r.sleep()
Expand All @@ -137,6 +138,7 @@ def parse_args():
arg_parser.add_argument("--trt_module", action='store_true')
arg_parser.add_argument("--pretrained_model", type=str, default='/home/shiozaki/work/experiments/models/checkpoints/sim_race_joycon_ResNet18_6_epoch=20.pth')
arg_parser.add_argument("--trt_model", type=str, default='road_following_model_trt.pth' )
arg_parser.add_argument("--image_topic_name", type=str, default='/front_camera/image_raw' )

args = arg_parser.parse_args()

Expand Down
4 changes: 3 additions & 1 deletion ai_race/learning/scripts/rosnode_inference_from_image.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,12 @@ def main():
rospack = rospkg.RosPack()
learning_pkg_path = rospack.get_path('learning')
trt_model_path = rospy.get_param('~trt_model')
image_topic_name = rospy.get_param('~image_topic_name')
#image_topic_name = "/front_camera/image_exp"

# call command
inference_from_image_path = learning_pkg_path + '/scripts/inference_from_image.py'
command = 'python' + ' ' + inference_from_image_path + ' ' + '--trt_module --trt_model' + ' ' + trt_model_path
command = 'python' + ' ' + inference_from_image_path + ' ' + '--trt_module --trt_model' + ' ' + trt_model_path + ' ' + "--image_topic_name" +' ' + image_topic_name
print(command)
subprocess.call(command.split())

Expand Down
28 changes: 12 additions & 16 deletions ai_race/learning/scripts/train.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@
import torch
import torch.nn as nn
import torch.optim as optim
import torch.nn.functional as F
import torch.backends.cudnn as cudnn
import torchvision
import torchvision.transforms as transforms
Expand All @@ -11,11 +10,11 @@
import os
import io
import argparse
import numpy as np
import pandas as pd
from sklearn.metrics import confusion_matrix
from sklearn.metrics import classification_report
from sklearn.metrics import f1_score
from sklearn.model_selection import train_test_split
from MyDataSet import MyDataset
from samplenet import SampleNet, SimpleNet

Expand All @@ -26,13 +25,18 @@ def main():

# Set device.
device = 'cuda' if torch.cuda.is_available() else 'cpu'
ROOT_DIR = ""
imgDataset = MyDataset(args.data_csv, ROOT_DIR, transform=transforms.ToTensor())
# Load dataset.
train_data, test_data = train_test_split(imgDataset, test_size=0.2)
pd.to_pickle(test_data, "test_data.pkl")
del test_data

# Prepare dataset.
np.random.seed(seed=0)
image_dataframe = pd.read_csv(args.data_csv, engine='python', header=None)
image_dataframe = image_dataframe.reindex(np.random.permutation(image_dataframe.index))
test_num = int(len(image_dataframe) * 0.2)
train_dataframe = image_dataframe[test_num:]
test_dataframe = image_dataframe[:test_num]
train_data = MyDataset(train_dataframe, transform=transforms.ToTensor())
test_data = MyDataset(test_dataframe, transform=transforms.ToTensor())
train_loader = torch.utils.data.DataLoader(train_data, batch_size=20, shuffle=True)
test_loader = torch.utils.data.DataLoader(test_data, batch_size=20)

print('data set')
# Set a model.
Expand Down Expand Up @@ -63,19 +67,11 @@ def main():

# Output score.
if(epoch%args.test_interval == 0):
pd.to_pickle(train_data, "train_data.pkl")
del train_data

test_data = pd.read_pickle("test_data.pkl")
test_loader = torch.utils.data.DataLoader(test_data, batch_size=20, shuffle=True)
del test_data
test_acc, test_loss = test(model, device, test_loader, criterion)
del test_loader

stdout_temp = 'epoch: {:>3}, train acc: {:<8}, train loss: {:<8}, test acc: {:<8}, test loss: {:<8}'
print(stdout_temp.format(epoch+1, train_acc, train_loss, test_acc, test_loss))

train_data = pd.read_pickle("train_data.pkl")
else:
stdout_temp = 'epoch: {:>3}, train acc: {:<8}, train loss: {:<8}' #, test acc: {:<8}, test loss: {:<8}'
print(stdout_temp.format(epoch+1, train_acc, train_loss)) #, test_acc, test_loss))
Expand Down
26 changes: 26 additions & 0 deletions ai_race/sim_environment/launch/image_republish.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
<?xml version="1.0"?>
<launch>
<arg name="input_image_topic" default="/front_camera/image_raw" />
<arg name="output_image_topic" default="/front_camera/image_exp" />
<arg name="use_compressed" default="true" />
<arg name="use_image_view" default="false" />

<group if="$(arg use_compressed)">
<node name="image_republish" pkg="image_transport" type="republish" args="compressed raw">
<remap from="in" to="$(arg input_image_topic)" />
<remap from="out" to="$(arg output_image_topic)" />
</node>
<group if="$(eval use_image_view==true)">
<node name="image_view" pkg="image_view" type="image_view" >
<remap from="image" to="$(arg output_image_topic)"/>
</node>
</group>
</group>
<group unless="$(arg use_compressed)">
<group if="$(eval use_image_view==true)">
<node name="image_view" pkg="image_view" type="image_view" >
<remap from="image" to="$(arg input_image_topic)"/>
</node>
</group>
</group>
</launch>
7 changes: 4 additions & 3 deletions ai_race/sim_environment/scripts/judge_communication_d.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,13 @@ class JudgeCommunicationd(object):
#jsonの内容
# judge_info

def __init__(self, judge_url, GameStateCallback_timer_duration):
def __init__(self, judge_url, GameStateCallback_timer_duration, Post_Ros_timer_duration):
self.judge_url = judge_url
self.vel_pub = rospy.Publisher('gamestate', String, queue_size=1)
#print(GameStateCallback_timer_duration)
rospy.Timer(rospy.Duration(GameStateCallback_timer_duration),
self.publishGameStateCallback)
rospy.Timer(rospy.Duration(GameStateCallback_timer_duration),
rospy.Timer(rospy.Duration(Post_Ros_timer_duration),
self.postRosTimerCallback)
self.tryCourseRecoveryCallback = rospy.Subscriber('gamestate', String, self.tryCourseRecoveryCallback)

Expand Down Expand Up @@ -98,7 +98,8 @@ def tryCourseRecoveryCallback(self, state):
JUDGE_URL = rospy.get_param('~judge_url', 'http://127.0.0.1:5000')
JUDGESERVER_GETSTATE_URL = JUDGE_URL + "/judgeserver/getState"
TIMER_DURATION = rospy.get_param('~GameStateCallback_timer_duration', 0.25)
JUDGECOMMUNICATIOND = JudgeCommunicationd(JUDGESERVER_GETSTATE_URL, TIMER_DURATION)
POST_ROSTIMER_DURATION = rospy.get_param('~PostRosTimerCallback_timer_duration', 0.25)
JUDGECOMMUNICATIOND = JudgeCommunicationd(JUDGESERVER_GETSTATE_URL, TIMER_DURATION, POST_ROSTIMER_DURATION)

rospy.spin()

Expand Down
Loading

0 comments on commit 2985085

Please sign in to comment.