Logical Camera Sensor - modulabs/gazebo-tutorial GitHub Wiki
Camera의 결과값이 image인 반면에, Logical camera의 결과값은 모델의 이름과 pose(position + orientation)이다. 이는 어떤 모델이 카메라에 보이는지 확인할 수 있다는 것이다.
- this world.를 다운로드 및 저장
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="default">
<include>
<uri>model://sun</uri>
</include>
<model name="post">
<pose>0 0 1 0 0 3.14159</pose>
<static>true</static>
<link name="link">
<sensor name="logical_camera" type="logical_camera">
<logical_camera>
<near>0.55</near>
<far>2.5</far>
<horizontal_fov>1.05</horizontal_fov>
<aspect_ratio>1.8</aspect_ratio>
</logical_camera>
<visualize>true</visualize>
<always_on>true</always_on>
<update_rate>10</update_rate>
</sensor>
</link>
</model>
<model name="target_box">
<static>true</static>
<pose>-2 0 1 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</visual>
</link>
</model>
</world>
</sdf>-
world 실행
gazebo --verbose ./tutorial_logical_camera.world -
Window->Topic Visualization (or press Ctrl-T) 클릭한다.
-
/gazebo/default/post/link/logical_camera/models topic를 선택한다.
- topic은 gazebo.msgs.LogicalCameraImage message 아래에 있다.
-
아래의 그림과 같은 결과를 볼 수 있을 것이다(?):
The logical camera reports the names and poses of models it sees.
While a normal camera sees <visual> geometry, the logical camera sees <collision>.
It works by testing if its frustum intersects the axis aligned bounding box (AABB) of a model.
The model's AABB is just big enough to contain all of its <collision> geometry.
Model names reported by the camera are scoped names.
A model in the world <model name="robot"> has a scoped named robot.
If it had a nested model <model name="hand">, the nested model's scoped name would be robot::hand.
The scoped name can be used to get a pointer to the model.
// Get the world (named "default")
gazebo::physics::WorldPtr world = physics::get_world("default");
// Get a model by name
gazebo::physics::ModelPtr handModel = world->GetModel("robot::hand");The logical camera outputs poses of models it sees relative to itself. It also outputs its own pose in world coordinates. Use this to get the model poses in world coordinates.
// msg is of type gazebo::msgs::LogicalCameraImage
// Pose of camera in world coordinates
ignition::math::Pose3d cameraPose = gazebo::msgs::ConvertIgn(msg.pose());
// Pose of first model relative to camera
ignition::math::Pose3d modelRelativePose = gazebo::msgs::ConvertIgn(msg.model(0).pose());
// Pose of first model in world coordinates
ignition::math::Pose3d modelWorldPose = modelRelativePose - cameraPose;The output of a logical camera may include a model a normal camera would not see if:
- The model has no
<visual>. - The
<visual>are transparent. - The
<collision>on the model are larger or in different places than the<visual>. - The model is occluded by another model.
- The model is rotated in the world such that its AABB is in the frustum while the geometry is not. Since the volume of a model's AABB is greater than or equal to the volume of the collisions on it, it is possible some part of this extra volume intersects the frustum while none of the collision geometry does. This is illustrated in the following image:
The output of a logical camera may not include a model a normal camera would see if:
- The
<visual>geometry is larger or in different places than the<collision> - The logical camera is on the model. The logical camera never includes the model it is part of in its output. However, it will include any nested or parent models.
- The only part of a model within the frustum is a nested model. A model's AABB does not contain its nested models. Every nested model has its own AABB. If only the nested model is visible then only it will be in the output.
#SDFormat Parameters
-
<update_rate>- 시뮬레이션 1초동안 센서가 데이터를 생성하는 숫자
-
<topic>- Gazebo가 topic을 publish에 옴기는것(?) 만약 이것이 정해지지 않는다면, 센서는 SDF파일에 있는 센서의 ancestor name을 포함한 topic 이름을 생성한다.
-
<pose>- 만약 모델, 링크, 센서의 pose가 모두 zero라면, world의 positive x축은 logical camera의 센터를 향할 것이다.
-
<visualize>- 만약 true라면, 카메라의 frustum(절두체?)은 gazebo client안에서 visualized될 것이다.
-
<logical_camera>-
<near>- pose of sensor로부터 clip plane 근처 가장 가까운 점까지의 거리 (unit: m).
-
<far>- pose of sensor로부터 clip plane 근처 가장 먼 점까지의 거리 (unit: m).
-
<horizontal_fov>*The horizontal field of view of the camera (unit: radians). -
<aspect_ratio>- 카메라 너비(width)와 높이(height)의 비율. horizontal field of view와 결합된 aspect ratio는 vertical field of view of the camera로 정의된다.
-
There are two ways to get the data: directly from the sensor, or using gazebo transport. Both ways return a LogicalCameraImage.
The data can be taken directly from the sensor. You will need to write a gazebo plugin to access it. Only the most recently generated message is available.
-
Get a generic sensor pointer using the name of the sensor.
gazebo::sensors::SensorPtr genericSensor = sensors::get_sensor("model_name::link_name::my_logical_camera") -
Cast it to a LogicalCameraSensor.
sensors::LogicalCameraSensorPtr logicalCamera = std::dynamic_pointer_cast<sensors::LogicalCameraSensor>(genericSensor);
-
Call LogicalCamera::Image() to get the latest sensor data.
gazebo::msgs::LogicalCameraImage sensorOutput = logicalCamera->Image();
Logical camera sensor data is published using gazebo transport. The data is published to subscribers immediately after it is generated.
-
Create a gazebo transport node and initialize it.
gazebo::transport::NodePtr node(new gazebo::transport::Node()); node->Init();
-
Create a callback for the subscription
///////////////////////////////////////////////// // Function is called everytime a message is received. void callback(gazebo::msgs::ConstLogicalCameraImagePtr &_msg) { // your code here }
-
Listen to the topic published by the logical camera
gazebo::transport::SubscriberPtr sub = node->Subscribe("~/post/link/logical_camera/models", callback);

