環境
この記事は以下の環境で動いています。
項目 | 値 |
---|---|
CPU | Core i5-8250U |
Ubuntu | 20.04 |
ROS | Noetic |
Gazebo | 11.9.0 |
インストールについてはROS講座02 インストールを参照してください。
またこの記事のプログラムはgithubにアップロードされています。ROS講座11 gitリポジトリを参照してください。
概要
Gazeboはデフォルトだとなんとなく暗いので明るさの設定をして明るくします。
Gazebo世界の色と明るさ
gazeboでは色の設定が3つの要素に行えます。
- シーン
gazeboワールドで1つ持っているパラメーターです。 - 物体
gazebo modelなどの各linkが該当します。 - ライト
gazebo中で置ける光源のことです。
シーン、ライト、物体のそれぞれが以下のようなパラメーターを持っている。
種類 | シーン | ライト | 物体 |
---|---|---|---|
Specular | o | o | |
Diffuse | o | o | |
Amdient | o | o | |
Emisive | o | ||
BackGround | o |
- SpecularとDiffuseはライトの値(0~1)と物体の値(0~1)の積になる。
- Amdientはシーンと物体の積
- BackGroundは背景の空の部分の色
- Emisiveは自発光の色、この値が強いとそのものが発行しているように見える。
- webの情報によると物体のSpecularはうまく適用できないらしい?
- シーンのAmdientを上げると全体的に明るくなる思った通りになる。
シーンの明るさの設定
以下のようにworldファイルに記述を加えます。するとambientのために全体的に明るくなります。backgroundは何もないところの色です。これが灰色->ほぼ黒に変化します。gazeboのデフォルトだと部屋が暗めなのでambientを上げます。
ソースファイル
以下がworldのanbientを設定している部分です。
<scene>
<ambient>0.7 0.7 0.7 1</ambient>
<background>0.1 0.1 0.1 1</background>
</scene>
実行
各ターミナルごとに実行前にsource ~/catkin_ws/devel/setup.bash
を実行する必要があります。
roslaunch gazebo_ros empty_world.launch world_name:=scene_lighting_default.world
roslaunch gazebo_ros empty_world.launch world_name:=scene_lighting_bright.world
オブジェクトの明るさの設定
ソースファイル
以下のようなモデルを追加します。
<model name="ColorModel">
<static>true</static>
<link name="link1">
<pose>0 0 0.5 0 0 0</pose>
<collision name="body_collision">
<geometry>
<box>
<size>0.5 0.5 0.5</size>
</box>
</geometry>
</collision>
<visual name="body_visual">
<material>
<ambient>0 0 0 1</ambient>
<diffuse>0 0 0 1</diffuse>
<specular>0 0 0 1</specular>
<emissive>0 0 0 1</emissive>
</material>
<geometry>
<box>
<size>0.5 0.5 0.5</size>
</box>
</geometry>
</visual>
</link>
<link name="link2">
<pose>1 0 0.5 0 0 0</pose>
<collision name="body_collision">
<geometry>
<box>
<size>0.5 0.5 0.5</size>
</box>
</geometry>
</collision>
<visual name="body_visual">
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0 0 0 1</diffuse>
<specular>0 0 0 1</specular>
<emissive>0 0 0 1</emissive>
</material>
<geometry>
<box>
<size>0.5 0.5 0.5</size>
</box>
</geometry>
</visual>
</link>
<link name="link3">
<pose>2 0 0.5 0 0 0</pose>
<collision name="body_collision">
<geometry>
<box>
<size>0.5 0.5 0.5</size>
</box>
</geometry>
</collision>
<visual name="body_visual">
<material>
<ambient>0 0 0 1</ambient>
<diffuse>1 0 0 1</diffuse>
<specular>0 0 0 1</specular>
<emissive>0 0 0 1</emissive>
</material>
<geometry>
<box>
<size>0.5 0.5 0.5</size>
</box>
</geometry>
</visual>
</link>
<link name="link4">
<pose>3 0 0.5 0 0 0</pose>
<collision name="body_collision">
<geometry>
<box>
<size>0.5 0.5 0.5</size>
</box>
</geometry>
</collision>
<visual name="body_visual">
<material>
<ambient>0 0 0 1</ambient>
<diffuse>0 0 0 1</diffuse>
<specular>1 0 0 1</specular>
<emissive>0 0 0 1</emissive>
</material>
<geometry>
<box>
<size>0.5 0.5 0.5</size>
</box>
</geometry>
</visual>
</link>
<link name="link5">
<pose>4 0 0.5 0 0 0</pose>
<collision name="body_collision">
<geometry>
<box>
<size>0.5 0.5 0.5</size>
</box>
</geometry>
</collision>
<visual name="body_visual">
<material>
<ambient>0 0 0 1</ambient>
<diffuse>0 0 0 1</diffuse>
<specular>0 0 0 1</specular>
<emissive>1 0 0 1</emissive>
</material>
<geometry>
<box>
<size>0.5 0.5 0.5</size>
</box>
</geometry>
</visual>
</link>
</model>
長々と書いていますが、実際は明るさが違うだけです。
link1 | link2 | link3 | link4 | link5 | |
---|---|---|---|---|---|
ambient | 0 | 1 | 0 | 0 | 0 |
diffuse | 0 | 0 | 1 | 0 | 0 |
specular | 0 | 0 | 0 | 1 | 0 |
emissive | 0 | 0 | 0 | 0 | 1 |
実行
各ターミナルごとに実行前にsource ~/catkin_ws/devel/setup.bash
を実行する必要があります。
roslaunch gazebo_ros empty_world.launch world_name:=model_color_variation.world
右から順にlink1,link2....
Specularはうまく適用されないみたいですね......。
ライトの適用
gazeboのlightは平行、点、スポットの3種類あります。
デフォルトのワールドでは斜めからの平行光のみなので、全体がのっぺりします。複数の点光源を並べえてみます。
ソースファイル
<light name='point_light_0' type='point'>
<pose frame=''>0 0 3 0 0 0</pose>
<diffuse>0.1 0.1 0.1 1</diffuse>
<specular>0.02 0.02 0.02 1</specular>
<attenuation>
<range>20</range>
<constant>0.5</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<cast_shadows>0</cast_shadows>
<direction>0 0 -1</direction>
</light>
<light name='point_light_1' type='point'>
<pose frame=''>4 0 3 0 0 0</pose>
<diffuse>0.1 0.1 0.1 1</diffuse>
<specular>0.02 0.02 0.02 1</specular>
<attenuation>
<range>20</range>
<constant>0.5</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<cast_shadows>0</cast_shadows>
<direction>0 0 -1</direction>
</light>
<light name='point_light_2' type='point'>
<pose frame=''>0 4 3 0 0 0</pose>
<diffuse>0.1 0.1 0.1 1</diffuse>
<specular>0.02 0.02 0.02 1</specular>
<attenuation>
<range>20</range>
<constant>0.5</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<cast_shadows>0</cast_shadows>
<direction>0 0 -1</direction>
</light>
<light name='point_light_3' type='point'>
<pose frame=''>4 4 3 0 0 0</pose>
<diffuse>0.1 0.1 0.1 1</diffuse>
<specular>0.02 0.02 0.02 1</specular>
<attenuation>
<range>20</range>
<constant>0.5</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<cast_shadows>0</cast_shadows>
<direction>0 0 -1</direction>
</light>
実行
各ターミナルごとに実行前にsource ~/catkin_ws/devel/setup.bash
を実行する必要があります。
Gazeboの基本図形を出すと以下のように表示されます。
roslaunch gazebo_ros empty_world.launch world_name:=light_variation.world
点光源を複数配置するときは、各々の明るさを下げ目に設定するのがコツです。