Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

カメラライントレースを修正 #49

Merged
merged 17 commits into from
Feb 5, 2024
Merged

カメラライントレースを修正 #49

merged 17 commits into from
Feb 5, 2024

Conversation

YusukeKato
Copy link
Contributor

@YusukeKato YusukeKato commented Jan 19, 2024

What does this implement/fix?

カメラライントレースサンプルを改善するために以下の修正を加えます。

  • READMEにRGBカメラによるライントレースの情報を追加
  • サンプルコースを走行できるように速度を調整
  • 2値化のしきい値をパラメータで設定できるように変更
  • その他の細かい修正

Does this close any currently open issues?

しません。

How has this been tested?

実機で下記のコマンドを実行してサンプルコースを走行できることを確認しました。

ros2 launch raspimouse_ros2_examples camera_line_follower.launch.py

シミュレータでも動作確認しました。

ros2 launch raspimouse_gazebo raspimouse_with_line_follower_field.launch.py use_rgb_camera:=true camera_downward:=true
ros2 launch raspimouse_ros2_examples camera_line_follower.launch.py mouse:=false use_camera_node:=false
ros2 topic pub --once /switches raspimouse_msgs/msg/Switches "{switch0: false, switch1: false, switch2: true}"

Any other comments?

ありません。

Checklists

@YusukeKato YusukeKato added the Type: Documentation Documentation only changes label Jan 19, 2024
@YusukeKato YusukeKato self-assigned this Jan 19, 2024
Copy link
Contributor

@ShotaAk ShotaAk left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

文章について一部コメントしてます。

実装に課題があるので調査してほしいです。

画像処理そのものにどれくらい時間が掛かっているのかも調査お願いします。

README.md Show resolved Hide resolved
README.md Show resolved Hide resolved
README.md Outdated Show resolved Hide resolved
@YusukeKato
Copy link
Contributor Author

camera_line_follower実行時の時間計測

  • ライン検出処理:20ms
  • 検出結果の画像トピックの配信処理(rqt_image_view実行中):30ms
    • rqt_image_viewを実行していない時は1ms以内
  • object_trackingもほぼ同じ処理時間

合計約50msの処理をカメラ画像トピック(30FPS)のコールバック関数内で行っているために、処理が間に合っていない可能性があります。

@ShotaAk
Copy link
Contributor

ShotaAk commented Jan 25, 2024

@YusukeKato
調査ありがとうございます。まずは画像処理の実装を変えてみましょうか。

どのステップでどれぐらい処理時間が掛かっているか、処理時間を短縮できるか、検証お願いします。

下記が候補です。
恐らく画像サイズを小さくするだけで、効果が出ると思います。

  • グレースケール変換と二値化
    • 対策:画像サイズを小さくする
  • ノイズ除去
    • 対策:cv::morphologyExのカーネルサイズを小さくする
  • 輪郭抽出
    • 対策:cv::findContours のオプションをCHAIN_APPROX_SIMPLEにする
  • 最大輪郭の抽出
    • 対策:輪郭抽出でCAHIN_APPROX_SIMPLEを適用する

@ShotaAk
Copy link
Contributor

ShotaAk commented Jan 25, 2024

画像のpublish処理については、画像サイズを小さくすれば改善すると思います。

また、image_transportを使うと改善する可能性あります。

https://github.com/ros-perception/image_transport_tutorials/blob/main/src/my_publisher.cpp#L26-L27

@YusukeKato
Copy link
Contributor Author

画像処理にかかった時間の計測結果は以下のようになりました。

合計

  • inRange() 使用時 : 10ms
  • adaptiveThreshold()使用時 : 27ms

内訳

  • グレースケール変換 : 1ms
  • 2値化
    • inRange() : 1ms
    • adaptiveThreshold() : 20ms
  • ノイズ除去
    • inRange()使用時 : 4ms
    • adaptiveThreshold() 使用時 : 2ms
  • 輪郭抽出 : 2ms
  • 最大輪郭の抽出 : 0.2msくらい
  • その他の処理 : 2ms

@YusukeKato
Copy link
Contributor Author

YusukeKato commented Jan 26, 2024

画像サイズを小さくしたときの画像処理とpublish処理にかかった時間を計測しました。

デフォルトの画像サイズの場合(640x480、2値化はinRange()を使用、rqt_image_view起動時)

  • 画像処理 : 10ms
  • publish : 60ms

画像サイズを320x240に変更した場合(2値化はinRange()を使用、rqt_image_view起動時)

  • 画像処理 : 5ms
  • publish : 9ms

画像サイズ320x240でadaptiveThreshold() を使用(rqt_image_view起動時)

  • 画像処理 : 10ms(そのうちadaptiveThreshold() が6ms)
  • publish : 9ms

画像サイズを小さくすることで画像処理とpublish処理に時間がかかりすぎる問題は解決しそうです。

@YusukeKato
Copy link
Contributor Author

ヒストグラム平坦化について調査しました。

参考 : https://docs.opencv.org/4.x/d6/dc7/group__imgproc__hist.html#ga7e54091f0c937d49bf84152a16f76d6e

使用方法

cv::equalizeHist(input_gray_image, output_hist_equalized_image);

ヒストグラム平坦化の処理にかかる時間は1ms以内でした。

ヒストグラム平坦化前のグレイスケール画像↓

gray

ヒストグラム平坦化を行ったグレイスケール画像↓

hist_equalized_gray

@YusukeKato
Copy link
Contributor Author

YusukeKato commented Jan 26, 2024

adaptiveThreshold関数によるグレイスケール画像の2値化

cv::adaptiveThreshold(gray, extracted_bin, 255, CV_ADAPTIVE_THRESH_GAUSSIAN_C, CV_THRESH_BINARY_INV, 51, 0);

adaptiveThreshold_image

ラインが一番大きい輪郭として検出されています。

Screenshot from 2024-01-26 16-37-04

@YusukeKato
Copy link
Contributor Author

YusukeKato commented Feb 2, 2024

usb_camをlaunchファイルから起動する際に、パラメータを設定してホワイトバランスと露光の自動調整機能をオフにしようとしましたが、うまくいきませんでした。そのため、以下のコマンドを実行して対処しています。

v4l2-ctl -c auto_exposure=1
v4l2-ctl -c white_balance_automatic=0

@YusukeKato YusukeKato changed the title READMEにカメラライントレースの情報を追記 カメラライントレースを修正 Feb 2, 2024
@ShotaAk
Copy link
Contributor

ShotaAk commented Feb 5, 2024

V4L2のパラメータ名が違うというのはissueにありました。
他の投稿を見ると、どうやらデバイスによって名称が変わるようです。
ros-drivers/usb_cam#260

Copy link
Contributor

@ShotaAk ShotaAk left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

シミュレータで動作確認しました。

ROS パラメータ変更が適用されてOKです。
コメントの確認お願いします。

README.md Outdated
[`./src/camera_line_follower_component.cpp`](./src/camera_line_follower_component.cpp)
を編集します。

物体検出精度が悪い時にはカメラの露光や関数内のパラメータを調整して下さい。
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

ROSパラメータが用意されたので、パラメータを変更して調整できることを説明してください。

raspimouse2 パッケージのREADMEのように、パラメータ一覧を記載するとわかりやすいです。

cmd_vel.linear.x = LINEAR_VEL * (object_normalized_area_ - TARGET_AREA);
cmd_vel.angular.z = ANGULAR_VEL * object_normalized_point_.x;
cmd_vel.linear.x = LINEAR_VEL;
cmd_vel.angular.z = ANGULAR_VEL * object_normalized_point_.x * 2.0;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

ここの2.0 がどういう意味なのかわかるように定数にしてください。

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

この2.0はデバッグ時に使用していた係数なので削除しました。

2.0を削除したことで回転方向の速度が変わりますが、ANGULAR_VELを調整することで対応できると思います。

constexpr double ANGULAR_VEL = -0.8;  // unit: rad/s

@ShotaAk
Copy link
Contributor

ShotaAk commented Feb 5, 2024

ついでに、ライン検出の関数名をdetecting_lineから、detect_lineに変更してもらえますか?

~ing という名称は、プロセスや状態に付けたいので。

@YusukeKato
Copy link
Contributor Author

コメントありがとうございます。

auto_exposurewhite_balance_automaticのパラメータに関して、いくつか名称を変更して試してみましたが、露光とホワイトバランスの自動調整はオフにできませんでした。

#49 (comment)

@ShotaAk
Copy link
Contributor

ShotaAk commented Feb 5, 2024

カメラパラメータについて言葉足らずでした。

他の投稿を見ると、どうやらデバイスによって名称が変わるようです。
なので、usb_cam側に柔軟なパラメータが必要ですね。

サンプルのlaunchファイル側でv4l2-ctrlコマンドを実行することもできますが、
カメラ機種依存になるのでいい方法ではないですね。

Copy link
Contributor

@ShotaAk ShotaAk left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

シミュレータで確認しました。

微修正お願いします。

README.en.md Outdated
Comment on lines 290 to 299
#### Configure

Edit [`./src/camera_line_follower_component.cpp`](./src/camera_line_follower_component.cpp)
to change a color of tracking target.

If the object detection accuracy is poor, adjust the camera exposure and parameters in the function

```cpp
cv::inRange(gray, 0, 100, extracted_bin);
```
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Parametersの説明が追加されたので、Configureの説明は削除してOKです

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

日本語READMEも同様にお願いします。

@@ -197,6 +203,10 @@ CallbackReturn Camera_Follower::on_configure(const rclcpp_lifecycle::State &)
switches_sub_ = create_subscription<raspimouse_msgs::msg::Switches>(
"switches", 1, std::bind(&Camera_Follower::callback_switches, this, std::placeholders::_1));

// Set parameter defaults
declare_parameter(BRIGHTNESS_MIN_VAL_PARAM, 0);
declare_parameter(BRIGHTNESS_MAX_VAL_PARAM, 100);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

image

私の環境だとライントレースに失敗します。

デフォルト値を90にしてもらえませんか?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

READMEに記載している数値も変更お願いします。

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

私の環境でもライントレースに失敗していました。

しきい値のデフォルト値を90に変更しました。

Copy link
Contributor

@ShotaAk ShotaAk left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTMです!

@ShotaAk ShotaAk merged commit 85b3bf0 into master Feb 5, 2024
2 checks passed
@ShotaAk ShotaAk deleted the update-readme branch February 5, 2024 09:52
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Type: Documentation Documentation only changes
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants