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

Update air sensor with air_speed.proto #374

Merged
merged 1 commit into from
Aug 15, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 3 additions & 4 deletions src/AirSpeedSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif
#include <gz/msgs/air_speed_sensor.pb.h>
#include <gz/msgs/air_speed.pb.h>
#if defined(_MSC_VER)
#pragma warning(pop)
#endif
Expand Down Expand Up @@ -113,7 +113,7 @@ bool AirSpeedSensor::Load(const sdf::Sensor &_sdf)
this->SetTopic("/air_speed");

this->dataPtr->pub =
this->dataPtr->node.Advertise<msgs::AirSpeedSensor>(
this->dataPtr->node.Advertise<msgs::AirSpeed>(
this->Topic());

if (!this->dataPtr->pub)
Expand Down Expand Up @@ -155,7 +155,7 @@ bool AirSpeedSensor::Update(
return false;
}

msgs::AirSpeedSensor msg;
msgs::AirSpeed msg;
*msg.mutable_header()->mutable_stamp() = msgs::Convert(_now);
auto frame = msg.mutable_header()->add_data();
frame->set_key("frame_id");
Expand Down Expand Up @@ -185,7 +185,6 @@ bool AirSpeedSensor::Update(
diff_pressure =
this->dataPtr->noises[AIR_SPEED_NOISE_PASCALS]->Apply(
diff_pressure);
msg.mutable_pressure_noise()->set_type(msgs::SensorNoise::GAUSSIAN);
}

msg.set_diff_pressure(diff_pressure * 100.0f);
Expand Down
4 changes: 2 additions & 2 deletions test/integration/air_speed.cc
Original file line number Diff line number Diff line change
Expand Up @@ -184,7 +184,7 @@ TEST_F(AirSpeedSensorTest, SensorReadings)
gz::math::Pose3d(0, 0, 1.5, 0, 0, 0) * sensorNoise->Pose());

// verify msg received on the topic
WaitForMessageTestHelper<gz::msgs::AirSpeedSensor> msgHelper(topic);
WaitForMessageTestHelper<gz::msgs::AirSpeed> msgHelper(topic);
EXPECT_TRUE(sensor->HasConnections());
sensor->Update(std::chrono::steady_clock::duration(std::chrono::seconds(1)));
EXPECT_TRUE(msgHelper.WaitForMessage()) << msgHelper;
Expand All @@ -195,7 +195,7 @@ TEST_F(AirSpeedSensorTest, SensorReadings)
EXPECT_DOUBLE_EQ(288.1369934082031, msg.temperature());

// verify msg with noise received on the topic
WaitForMessageTestHelper<gz::msgs::AirSpeedSensor>
WaitForMessageTestHelper<gz::msgs::AirSpeed>
msgHelperNoise(topicNoise);
sensorNoise->Update(std::chrono::steady_clock::duration(
std::chrono::seconds(1)), false);
Expand Down
Loading