Skip to content

Commit

Permalink
Merge pull request #202 from ignitionrobotics/chapulina/3_to_5
Browse files Browse the repository at this point in the history
3 ➡️ 5
  • Loading branch information
ahcorde authored Mar 4, 2022
2 parents fe65a92 + aae1f7c commit 135d876
Show file tree
Hide file tree
Showing 15 changed files with 58 additions and 12 deletions.
8 changes: 8 additions & 0 deletions include/ignition/sensors/Sensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -180,6 +180,14 @@ namespace ignition
/// \return Name of sensor.
public: std::string Name() const;

/// \brief FrameId.
/// \return FrameId of sensor.
public: std::string FrameId() const;

/// \brief Set Frame ID of the sensor
/// \param[in] _frameId Frame ID of the sensor
public: void SetFrameId(const std::string &_frameId);

/// \brief Get topic where sensor data is published.
/// \return Topic sensor publishes data to
public: std::string Topic() const;
Expand Down
2 changes: 1 addition & 1 deletion src/AirPressureSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ bool AirPressureSensor::Update(
*msg.mutable_header()->mutable_stamp() = msgs::Convert(_now);
auto frame = msg.mutable_header()->add_data();
frame->set_key("frame_id");
frame->add_value(this->Name());
frame->add_value(this->FrameId());

// This block of code comes from RotorS:
// https://github.com/ethz-asl/rotors_simulator/blob/master/rotors_gazebo_plugins/src/gazebo_pressure_plugin.cpp
Expand Down
2 changes: 1 addition & 1 deletion src/AltimeterSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -153,7 +153,7 @@ bool AltimeterSensor::Update(const std::chrono::steady_clock::duration &_now)
*msg.mutable_header()->mutable_stamp() = msgs::Convert(_now);
auto frame = msg.mutable_header()->add_data();
frame->set_key("frame_id");
frame->add_value(this->Name());
frame->add_value(this->FrameId());

// Apply altimeter vertical position noise
if (this->dataPtr->noises.find(ALTIMETER_VERTICAL_POSITION_NOISE_METERS) !=
Expand Down
4 changes: 2 additions & 2 deletions src/CameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -407,7 +407,7 @@ bool CameraSensor::Update(const std::chrono::steady_clock::duration &_now)
*msg.mutable_header()->mutable_stamp() = msgs::Convert(_now);
auto frame = msg.mutable_header()->add_data();
frame->set_key("frame_id");
frame->add_value(this->Name());
frame->add_value(this->FrameId());
msg.set_data(data, this->dataPtr->camera->ImageMemorySize());
}

Expand Down Expand Up @@ -620,7 +620,7 @@ void CameraSensor::PopulateInfo(const sdf::Camera *_cameraSdf)
// can populate it with arbitrary frames.
auto infoFrame = this->dataPtr->infoMsg.mutable_header()->add_data();
infoFrame->set_key("frame_id");
infoFrame->add_value(this->Name());
infoFrame->add_value(this->FrameId());

this->dataPtr->infoMsg.set_width(width);
this->dataPtr->infoMsg.set_height(height);
Expand Down
2 changes: 1 addition & 1 deletion src/DepthCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -551,7 +551,7 @@ bool DepthCameraSensor::Update(
*msg.mutable_header()->mutable_stamp() = msgs::Convert(_now);
auto frame = msg.mutable_header()->add_data();
frame->set_key("frame_id");
frame->add_value(this->Name());
frame->add_value(this->FrameId());

std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
msg.set_data(this->dataPtr->depthBuffer,
Expand Down
2 changes: 1 addition & 1 deletion src/ImuSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -222,7 +222,7 @@ bool ImuSensor::Update(const std::chrono::steady_clock::duration &_now)
msg.set_entity_name(this->Name());
auto frame = msg.mutable_header()->add_data();
frame->set_key("frame_id");
frame->add_value(this->Name());
frame->add_value(this->FrameId());

if (this->dataPtr->orientationEnabled)
{
Expand Down
5 changes: 4 additions & 1 deletion src/Lidar.cc
Original file line number Diff line number Diff line change
Expand Up @@ -245,8 +245,11 @@ bool Lidar::PublishLidarScan(const std::chrono::steady_clock::duration &_now)
this->dataPtr->laserMsg.mutable_header()->clear_data();
auto frame = this->dataPtr->laserMsg.mutable_header()->add_data();
frame->set_key("frame_id");
// keeping here the sensor name instead of frame_id because the visualizeLidar
// plugin relies on this value to get the position of the lidar.
// the ros_ign plugin is using the laserscan.proto 'frame' field
frame->add_value(this->Name());
this->dataPtr->laserMsg.set_frame(this->Name());
this->dataPtr->laserMsg.set_frame(this->FrameId());

// Store the latest laser scans into laserMsg
msgs::Set(this->dataPtr->laserMsg.mutable_world_pose(),
Expand Down
2 changes: 1 addition & 1 deletion src/LogicalCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ bool LogicalCameraSensor::Update(
this->dataPtr->msg.mutable_header()->clear_data();
auto frame = this->dataPtr->msg.mutable_header()->add_data();
frame->set_key("frame_id");
frame->add_value(this->Name());
frame->add_value(this->FrameId());

// publish
this->AddSequence(this->dataPtr->msg.mutable_header());
Expand Down
2 changes: 1 addition & 1 deletion src/MagnetometerSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -175,7 +175,7 @@ bool MagnetometerSensor::Update(
*msg.mutable_header()->mutable_stamp() = msgs::Convert(_now);
auto frame = msg.mutable_header()->add_data();
frame->set_key("frame_id");
frame->add_value(this->Name());
frame->add_value(this->FrameId());

// Apply magnetometer noise after converting to body frame
if (this->dataPtr->noises.find(MAGNETOMETER_X_NOISE_TESLA) !=
Expand Down
4 changes: 2 additions & 2 deletions src/RgbdCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -475,7 +475,7 @@ bool RgbdCameraSensor::Update(const std::chrono::steady_clock::duration &_now)
*msg.mutable_header()->mutable_stamp() = msgs::Convert(_now);
auto frame = msg.mutable_header()->add_data();
frame->set_key("frame_id");
frame->add_value(this->Name());
frame->add_value(this->FrameId());

std::lock_guard<std::mutex> lock(this->dataPtr->mutex);

Expand Down Expand Up @@ -587,7 +587,7 @@ bool RgbdCameraSensor::Update(const std::chrono::steady_clock::duration &_now)
*msg.mutable_header()->mutable_stamp() = msgs::Convert(_now);
auto frame = msg.mutable_header()->add_data();
frame->set_key("frame_id");
frame->add_value(this->Name());
frame->add_value(this->FrameId());
msg.set_data(data, rendering::PixelUtil::MemorySize(rendering::PF_R8G8B8,
width, height));

Expand Down
28 changes: 28 additions & 0 deletions src/Sensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,9 @@ class ignition::sensors::SensorPrivate
/// A map is used so that a single sensor can have multiple sensor
/// streams each with a sequence counter.
public: std::map<std::string, uint64_t> sequences;

/// \brief frame id
public: std::string frame_id;
};

SensorId SensorPrivate::idCounter = 0;
Expand Down Expand Up @@ -136,6 +139,19 @@ bool SensorPrivate::PopulateFromSDF(const sdf::Sensor &_sdf)
return false;
}

sdf::ElementPtr element = _sdf.Element();
if (element)
{
if (element->HasElement("ignition_frame_id"))
{
this->frame_id = element->Get<std::string>("ignition_frame_id");
}
else
{
this->frame_id = this->name;
}
}

// Try resolving the pose first, and only use the raw pose if that fails
auto semPose = _sdf.SemanticPose();
sdf::Errors errors = semPose.Resolve(this->pose);
Expand Down Expand Up @@ -226,6 +242,18 @@ std::string Sensor::Name() const
return this->dataPtr->name;
}

//////////////////////////////////////////////////
std::string Sensor::FrameId() const
{
return this->dataPtr->frame_id;
}

//////////////////////////////////////////////////
void Sensor::SetFrameId(const std::string &_frameId)
{
this->dataPtr->frame_id = _frameId;
}

//////////////////////////////////////////////////
std::string Sensor::Topic() const
{
Expand Down
4 changes: 4 additions & 0 deletions src/Sensor_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,10 @@ TEST(Sensor_TEST, Sensor)
EXPECT_EQ(1u, sensor.Id());

EXPECT_EQ(nullptr, sensor.SDF());

EXPECT_EQ(sensor.Name(), sensor.FrameId());
sensor.SetFrameId("frame_id_12");
EXPECT_EQ(std::string("frame_id_12"), sensor.FrameId());
}

//////////////////////////////////////////////////
Expand Down
2 changes: 1 addition & 1 deletion src/ThermalCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -463,7 +463,7 @@ bool ThermalCameraSensor::Update(
*stamp = msgs::Convert(_now);
auto frame = this->dataPtr->thermalMsg.mutable_header()->add_data();
frame->set_key("frame_id");
frame->add_value(this->Name());
frame->add_value(this->FrameId());

std::lock_guard<std::mutex> lock(this->dataPtr->mutex);

Expand Down
2 changes: 2 additions & 0 deletions test/integration/camera_plugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,8 @@ void CameraSensorTest::ImagesWithBuiltinSDF(const std::string &_renderEngine)
EXPECT_EQ(256u, sensor->ImageWidth());
EXPECT_EQ(257u, sensor->ImageHeight());

EXPECT_EQ(std::string("base_camera"), sensor->FrameId());

std::string topic = "/test/integration/CameraPlugin_imagesWithBuiltinSDF";
WaitForMessageTestHelper<ignition::msgs::Image> helper(topic);

Expand Down
1 change: 1 addition & 0 deletions test/integration/camera_sensor_builtin.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
<link name="link1">
<sensor name="camera1" type="camera">
<update_rate>10</update_rate>
<ignition_frame_id>base_camera</ignition_frame_id>
<topic>/test/integration/CameraPlugin_imagesWithBuiltinSDF</topic>
<camera>
<horizontal_fov>1.05</horizontal_fov>
Expand Down

0 comments on commit 135d876

Please sign in to comment.