-
Notifications
You must be signed in to change notification settings - Fork 261
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
Add QoS profiles field to metadata struct and provide serialization utilities #330
Changes from all commits
e6c64ef
6ee2b30
9d86df5
1dfc541
90b93db
98f2ddc
84ac660
99e8ed3
aa9d0a4
7ba5585
1fe86ce
b715038
5b5caf6
aa55d43
d0802b3
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change | ||||||||
---|---|---|---|---|---|---|---|---|---|---|
@@ -0,0 +1,70 @@ | ||||||||||
// Copyright 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved. | ||||||||||
// | ||||||||||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||||||||||
// you may not use this file except in compliance with the License. | ||||||||||
// You may obtain a copy of the License at | ||||||||||
// | ||||||||||
// http://www.apache.org/licenses/LICENSE-2.0 | ||||||||||
// | ||||||||||
// Unless required by applicable law or agreed to in writing, software | ||||||||||
// distributed under the License is distributed on an "AS IS" BASIS, | ||||||||||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||||||||||
// See the License for the specific language governing permissions and | ||||||||||
// limitations under the License. | ||||||||||
|
||||||||||
#include "qos.hpp" | ||||||||||
|
||||||||||
namespace YAML | ||||||||||
{ | ||||||||||
Node convert<rmw_time_t>::encode(const rmw_time_t & time) | ||||||||||
{ | ||||||||||
Node node; | ||||||||||
node["sec"] = time.sec; | ||||||||||
node["nsec"] = time.nsec; | ||||||||||
return node; | ||||||||||
} | ||||||||||
|
||||||||||
bool convert<rmw_time_t>::decode(const Node & node, rmw_time_t & time) | ||||||||||
{ | ||||||||||
time.sec = node["sec"].as<uint>(); | ||||||||||
time.nsec = node["nsec"].as<uint>(); | ||||||||||
Comment on lines
+29
to
+30
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I think this would fix it, |
||||||||||
return true; | ||||||||||
} | ||||||||||
|
||||||||||
Node convert<rosbag2_transport::Rosbag2QoS>::encode(const rosbag2_transport::Rosbag2QoS & qos) | ||||||||||
{ | ||||||||||
const auto & p = qos.get_rmw_qos_profile(); | ||||||||||
Node node; | ||||||||||
node["history"] = static_cast<int>(p.history); | ||||||||||
node["depth"] = p.depth; | ||||||||||
node["reliability"] = static_cast<int>(p.reliability); | ||||||||||
node["durability"] = static_cast<int>(p.durability); | ||||||||||
node["deadline"] = p.deadline; | ||||||||||
node["lifespan"] = p.lifespan; | ||||||||||
node["liveliness"] = static_cast<int>(p.liveliness); | ||||||||||
node["liveliness_lease_duration"] = p.liveliness_lease_duration; | ||||||||||
node["avoid_ros_namespace_conventions"] = p.avoid_ros_namespace_conventions; | ||||||||||
return node; | ||||||||||
} | ||||||||||
|
||||||||||
bool convert<rosbag2_transport::Rosbag2QoS>::decode( | ||||||||||
const Node & node, rosbag2_transport::Rosbag2QoS & qos) | ||||||||||
{ | ||||||||||
auto history = static_cast<rmw_qos_history_policy_t>(node["history"].as<int>()); | ||||||||||
auto reliability = static_cast<rmw_qos_reliability_policy_t>(node["reliability"].as<int>()); | ||||||||||
auto durability = static_cast<rmw_qos_durability_policy_t>(node["durability"].as<int>()); | ||||||||||
auto liveliness = static_cast<rmw_qos_liveliness_policy_t>(node["liveliness"].as<int>()); | ||||||||||
|
||||||||||
qos | ||||||||||
.keep_last(node["depth"].as<int>()) | ||||||||||
.history(history) | ||||||||||
.reliability(reliability) | ||||||||||
.durability(durability) | ||||||||||
.deadline(node["deadline"].as<rmw_time_t>()) | ||||||||||
.lifespan(node["lifespan"].as<rmw_time_t>()) | ||||||||||
.liveliness(liveliness) | ||||||||||
.liveliness_lease_duration(node["liveliness_lease_duration"].as<rmw_time_t>()) | ||||||||||
.avoid_ros_namespace_conventions(node["avoid_ros_namespace_conventions"].as<bool>()); | ||||||||||
Comment on lines
+58
to
+67
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I know it's a hard problem to solve, but any idea about how we could try to keep this in sync as qos gets new fields? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I don't have a good answer to this. My thought as of right now is just that rosbag2 needs to have a pass to support new fields if they are added, and until that time it will only support the default values for any given policy. I'm not aware of a way to introspect fields of a struct in C++, but that doesn't mean there isn't a way There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Ah - I thought of something we can do. It is a "change detector" like we try to avoid, but in this case of serialization method, it seems like the right thing to do. I'm adding a test that explicitly builds a rmw_qos_profile_t using {} initializer, so if new fields are added, the build will fail. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Thinking about it, There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. If you're sure the qos struct will always be a POD, memcmp is an option otherwise (tread carefully as it can blow up easily) There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I don't think it will. If new fields are added - when I construct the object it will use the default values for those new fields. Now when I serialize, it will write out all the fields we specified here. Then, on deserializing, it will read the fields that it knows, with the unknown fields having default values. The equality will pass and new fields will have slipped through undetected There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. we could maybe apply something like a builder pattern which only allows to build the object if all parts are present. But I don't see a real way around updating the code base if the QoS struct gets more fields. |
||||||||||
return true; | ||||||||||
} | ||||||||||
} // namespace YAML |
Original file line number | Diff line number | Diff line change | ||
---|---|---|---|---|
@@ -0,0 +1,66 @@ | ||||
// Copyright 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved. | ||||
// | ||||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||||
// you may not use this file except in compliance with the License. | ||||
// You may obtain a copy of the License at | ||||
// | ||||
// http://www.apache.org/licenses/LICENSE-2.0 | ||||
// | ||||
// Unless required by applicable law or agreed to in writing, software | ||||
// distributed under the License is distributed on an "AS IS" BASIS, | ||||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||||
// See the License for the specific language governing permissions and | ||||
// limitations under the License. | ||||
|
||||
#ifndef ROSBAG2_TRANSPORT__QOS_HPP_ | ||||
#define ROSBAG2_TRANSPORT__QOS_HPP_ | ||||
|
||||
#include "rclcpp/qos.hpp" | ||||
|
||||
#ifdef _WIN32 | ||||
// This is necessary because of a bug in yaml-cpp's cmake | ||||
#define YAML_CPP_DLL | ||||
// This is necessary because yaml-cpp does not always use dllimport/dllexport consistently | ||||
# pragma warning(push) | ||||
# pragma warning(disable:4251) | ||||
# pragma warning(disable:4275) | ||||
#endif | ||||
#include "yaml-cpp/yaml.h" | ||||
#ifdef _WIN32 | ||||
# pragma warning(pop) | ||||
#endif | ||||
|
||||
|
||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||
namespace rosbag2_transport | ||||
{ | ||||
/// Simple wrapper around rclcpp::QoS to provide a default constructor for YAML deserialization. | ||||
class Rosbag2QoS : public rclcpp::QoS | ||||
{ | ||||
public: | ||||
Rosbag2QoS() | ||||
: rclcpp::QoS(0) {} // 0 history depth is always overwritten on deserializing | ||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I guess we could also default to There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Note that But, I will instantiate this with the default profile (not system_default) |
||||
explicit Rosbag2QoS(const rclcpp::QoS & value) | ||||
: rclcpp::QoS(value) {} | ||||
}; | ||||
} // namespace rosbag2_transport | ||||
|
||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||
|
||||
namespace YAML | ||||
{ | ||||
template<> | ||||
struct convert<rmw_time_t> | ||||
{ | ||||
static Node encode(const rmw_time_t & time); | ||||
static bool decode(const Node & node, rmw_time_t & time); | ||||
}; | ||||
|
||||
template<> | ||||
struct convert<rosbag2_transport::Rosbag2QoS> | ||||
{ | ||||
static Node encode(const rosbag2_transport::Rosbag2QoS & qos); | ||||
static bool decode(const Node & node, rosbag2_transport::Rosbag2QoS & qos); | ||||
}; | ||||
} // namespace YAML | ||||
|
||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||
|
||||
#endif // ROSBAG2_TRANSPORT__QOS_HPP_ |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
is it the right time to update the bag metadata? Could we delay that until the feature is built completely? What's the impact if we were to release rosbag2 just after this PR gets merged?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Yeah I was considering this, but I think that now is the time because now is when the data model actually changes. Moving forward that model will just start to hold more useful values. If we were to release this now, nothing bad would happen, it's fully backward compatible with previous metadata versions.