Skip to content

Commit

Permalink
Tweaks
Browse files Browse the repository at this point in the history
Signed-off-by: Carlos Agüero <[email protected]>
  • Loading branch information
caguero committed Mar 29, 2024
1 parent f3d9b84 commit cc22207
Show file tree
Hide file tree
Showing 5 changed files with 25 additions and 8 deletions.
2 changes: 1 addition & 1 deletion ros_gz_bridge/include/ros_gz_bridge/ros_gz_bridge.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ class RosGzBridge : public rclcpp::Node
rclcpp::TimerBase::SharedPtr heartbeat_timer_;

/// \brief Whether the config_file parameter was parsed or not.
bool config_file_parsed_;
bool config_file_parsed_{false};
};
} // namespace ros_gz_bridge

Expand Down
23 changes: 21 additions & 2 deletions ros_gz_bridge/src/bridge_config.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -174,13 +174,32 @@ std::vector<BridgeConfig> readFromYaml(std::istream & in)
std::vector<BridgeConfig> readFromYamlFile(const std::string & filename)
{
std::vector<BridgeConfig> ret;
resource_retriever::Retriever r;
std::ifstream in(filename);
resource_retriever::Retriever retriever;
resource_retriever::MemoryResource res;

auto logger = rclcpp::get_logger("readFromYamlFile");

if (in.is_open()) {
// Compute file size to warn on empty configuration
const auto fbegin = in.tellg();
in.seekg(0, std::ios::end);
const auto fend = in.tellg();
const auto fsize = fend - fbegin;

if (fsize == 0) {
RCLCPP_ERROR(
logger,
"Could not parse config: file empty [%s]", filename.c_str());
return ret;
}

in.seekg(0, std::ios::beg);
return readFromYaml(in);
}

try {
res = r.get(filename);
res = retriever.get(filename);
} catch (const resource_retriever::Exception & exc) {
RCLCPP_ERROR(
logger,
Expand Down
3 changes: 1 addition & 2 deletions ros_gz_bridge/src/ros_gz_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,7 @@ namespace ros_gz_bridge
{

RosGzBridge::RosGzBridge(const rclcpp::NodeOptions & options)
: rclcpp::Node("ros_gz_bridge", options),
config_file_parsed_(false)
: rclcpp::Node("ros_gz_bridge", options)
{
gz_node_ = std::make_shared<gz::transport::Node>();

Expand Down
5 changes: 2 additions & 3 deletions ros_gz_bridge/test/bridge_config.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,9 +70,8 @@ class BridgeConfig : public ::testing::Test

TEST_F(BridgeConfig, Minimum)
{
auto results = ros_gz_bridge::readFromYamlFile(
"package://ros_gz_bridge/test/config/minimum.yaml");
EXPECT_EQ(4u, results.size());
auto results = ros_gz_bridge::readFromYamlFile("test/config/minimum.yaml");
ASSERT_EQ(4u, results.size());

{
auto config = results[0];
Expand Down
File renamed without changes.

0 comments on commit cc22207

Please sign in to comment.