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

Modified scan2image & calibration_test for calibration_publisher node #101

Merged
merged 8 commits into from
Nov 16, 2015
Merged

Conversation

yukkysaito
Copy link
Contributor

No description provided.

static Image_points_dataset image_points_dataset;
static int i;
static int count;
static int stored_num[MAX_IMAGE_WIDTH * MAX_IMAGE_HEIGHT];
Copy link

Choose a reason for hiding this comment

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

このあたりの変数は staticである必要があるのでしょうか ?
icountは必要でないように思えますが...

@yukkysaito
Copy link
Contributor Author

本コードは、私がフルスクラッチしたものですが、ROSのチュートリアルのファイル(https://github.com/ros/ros_tutorials/hydro-devel/roscpp_tutorials/listener/listener.cpp )を複製してファイルを生成してコードを記述していったためライセンスが残っておりました。
このような場合、どのようにしたほうがよろしいでしょうか?実際ベースにした範囲はmain関数の定義ぐらいです。

@syohex
Copy link

syohex commented Oct 29, 2015

@yukkysaito それであれば書き換えても問題ないと思うのですが, できましたらその旨をコミットログに書いていただけないでしょうか. 今後からで良いので.

Correct copyright license

Because all of this code is written by me.

全員(弊社含む)に言えるのかもしれないですが, コミットログはより具体的に書いていただけるとよいと思います(コードを変更したとかは見ればわかるので, 特に書く必要はない). バグを直した場合は, こういう場合にバグが発生したので直したとか具体的に書いてあると後からログを見た時にどういう修正をしたかが理解しやすくなります.

例えば 96c3b77 の場合, fixed bug of initとありますが, これだけでは意味を把握することが難しいです. 私自身理解できていないので間違っているかもしれないですが, zero clearしていないので○○な問題が発生していたとか, 最後に max_y, min_yNO_DATAにリセットしていなかったため xxな問題が起きていた等も記述していただけるとよいかと思います. (後から見た時に同じ問題に気をつけないともなります).

githubを利用しているので issueを立てそこに具体的な問題を書き, Fix issue #xxのように書くのでもよいかと思います. (この場合でも具体的にコミットログを書くに越したことはないですが)

because variables (i, count) do not needed static var.
@yukkysaito
Copy link
Contributor Author

承知いたしました。アドバイスありがとうございます。

i, count のstaticに関して 407a7a8 にて修正いたしました。

@syohex
Copy link

syohex commented Oct 30, 2015

@manato 全体の確認をお願いします. (私では意味的なレベルで把握できないため)

#define IMAGE_WIDTH 800
#define IMAGE_HEIGHT 600
#define MAX_IMAGE_WIDTH 800
#define MAX_IMAGE_HEIGHT 600
Copy link

Choose a reason for hiding this comment

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

なるべく画像サイズの固定値は排除したいのですが、ここは800x600に固定しなければならない箇所でしょうか?
画像サイズはsensor_msgs/Image型の場合各々height, widthというメンバから取得出来ます(http://docs.ros.org/api/sensor_msgs/html/msg/Image.html)

Copy link
Contributor Author

Choose a reason for hiding this comment

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

画像サイズは固定ではありません。calibration publisherから配信されたトピックのサイズに自動的に設定するようになっております。
その場合、配列を動的に確保する必要があり、毎コールバックでmalloc(calloc)で確保するとリアルタイム性が損なわれるので、毎コールバックで0に初期化するために静的配列を生成するようにしました。この配列は静的に確保するのですが、最大800x600までの画像に対応できるようにMAX_IMAGE_WIDTH、MAX_IMAGE_HEIGHTというのを作成しました。
現状800x600以下であればどんな画像サイズでも大丈夫になっています。

Copy link

Choose a reason for hiding this comment

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

@yukkysaito さん,

あまり綺麗な方法ではないかもしれませんが,例えば以下の方法でまず画像サイズを
取得してから,そのサイズに合わせて静的配列を確保するのは如何でしょうか?

  1. main関数内でまず/image_rawのCallback関数を呼び出す

  2. Callback関数内では,トピックから画像サイズを大域変数へ読込み,
    代入が完了したらフラグを立てる(isReady = true;といった感じで)

  3. main関数の方では,/image_rawのCallback呼び出し直後に下記のようなループで
    画像サイズが取得できるまで待つ

    /* 1秒ごとにCallbackを呼び,画像サイズが取得できるまで待つ */
    ros::Rate rate(1);
    while (isReady != true) {
      ros::spinOnce();
      rate.sleep();
    }
    
    /* 
      画像サイズが確保できたら,そのサイズを基に静的配列の確保し,
      その後の処理をすすめる
    */

Autowareを公開するようになってから気づいたのですが,画像サイズに関しての需要は
様々で,なるべく大きい画像サイズを使いたいと言う声もよく聞くので,対応する画像サイズが800x600以下と言う制約はなるべく無いほうが良い様に思われます.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

@manato
ご指摘ありがとうございます。
現状の実装では以下のようになっております。
1.main関数内でまずcalibration publisherのCallback関数を呼び出す
2.Callback関数内では,トピックから画像サイズを大域変数へ読込み, 代入が完了したらフラグを立てる(isReady = true;といった感じで)
3.画像サイズが確定後、領域を確保し、scan2imageの本体を処理実行

しかしながら、静的配列はコンパイル時に確保する値が決まっていないといけないため、以下のような実装は言語仕様上できません。

/* 1秒ごとにCallbackを呼び,画像サイズが取得できるまで待つ */
ros::Rate rate(1);
while (isReady != true) {
  ros::spinOnce();
  rate.sleep();
}

/* 
  画像サイズが確保できたら,そのサイズを基に静的配列の確保し,
  その後の処理をすすめる
*/

したがって、今回、静的確保するため最大値という形でMAX_IMAGE_WIDTH、MAX_IMAGE_HEIGHTを定義しておりました。現在、callocで確保した領域(画像サイズ)を毎コールバックで再利用するため、毎回確保した領域をcleanな状態にしなければいけません。(毎コールバックの画像領域の動的確保は好ましくない)
このcleanする方法として、「確保した全領域に0をコピーする」もしくは「代入された領域のみを記憶し、その場所のみ0をコピーする」の2択になると思います。前者の場合は、MAX_IMAGE_WIDTH、MAX_IMAGE_HEIGHTは必要なくなりますが、画像全領域に0コピーを行う必要があります。後者の場合は、MAX_IMAGE_WIDTH、MAX_IMAGE_HEIGHTが必要になりますが、ピンポイントの0コピーが可能です。
今回、後者を選んだ理由としては、scan2imageでは画像にプロジェクションする点群は非常に少ないので、全領域に0をコピーするより、ピンポイントで初期化したほうがいいのではないかと思いこのような実装にしました。
どちらもメリット・デメリットがあるのですが、どのようにしたほうがよろしいでしょうか?

Copy link

Choose a reason for hiding this comment

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

しかしながら、静的配列はコンパイル時に確保する値が決まっていないといけないため、以下のような実装は言語仕様上できません

すみません.うっかりしていました...

今回の場合であれば,「確保した全領域に対して0をセット」すると言うことで
memset(&image, 0, sizeof(image))のような形で毎コールバックごとに初期化してしまえば
良いと思います.(恐らくそんなにコストの高い命令では無いはずですので...)

Copy link
Contributor Author

Choose a reason for hiding this comment

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

本件について abaaa12 にて修正いたしました。
お忙しいところチェック・アドバイスしていただき大変助かりました。
ありがとうございます。

追記:すいません。もう少し、マージを待ってもらえますか?
追記2:動作確認を行い正常に動作することを確認できました。よければマージをお願いできますでしょうか?

Yukihiro Saito added 3 commits November 2, 2015 13:27
( add memset() instead of them )
the third argument in memset() is wrong
@yukkysaito
Copy link
Contributor Author

@syohex アドバイスありがとうございます。
アドバイスを参考にfill_nへ変更いたしました。
よければマージをお願いいたします

yukkysaito pushed a commit that referenced this pull request Nov 16, 2015
Modified scan2image & calibration_test for calibration_publisher node
@yukkysaito yukkysaito merged commit bf4b23e into autowarefoundation:master Nov 16, 2015
@mitsudome-r mitsudome-r added the version:autoware-ai Autoware.AI label Jun 14, 2022
youtalk added a commit that referenced this pull request Sep 4, 2024
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants