While a camera outputs an image, a logical camera outputs model names and poses. It shows which models might be visible to a camera in the same location.
Download and save 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>
Launch the world
gazebo --verbose ./tutorial_logical_camera.world
From the top menu click Window then Topic Visualization.
Select the topic /gazebo/default/post/link/logical_camera/models.
You should see the following:
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:
<visual>
.<visual>
are transparent.<collision>
on the model are larger or in different places than the <visual>
.The output of a logical camera may not include a model a normal camera would see if:
<visual>
geometry is larger or in different places than the <collision>
<update_rate>
<topic>
<pose>
<visualize>
<logical_camera>
<near>
<far>
<horizontal_fov>
<aspect_ratio>
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);