Skip to content

Commit b2f8f91

Browse files
committed
add helper for evaluation (qos, publish, publish qos)
1 parent fcd1f6b commit b2f8f91

File tree

2 files changed

+34
-19
lines changed

2 files changed

+34
-19
lines changed

hardware_interface/include/hardware_interface/distributed_control_interface/command_forwarder.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -71,6 +71,8 @@ class CommandForwarder final
7171
rclcpp::Publisher<controller_manager_msgs::msg::Evaluation>::SharedPtr evaluation_pub_;
7272
const std::string evaluation_type_ = "commandInterface";
7373
std::string evaluation_identifier_;
74+
bool publish_evaluation_msg_;
75+
rclcpp::Time receive_time_;
7476
};
7577

7678
} // namespace distributed_control

hardware_interface/src/hardware_interface/distributed_control_interface/command_forwarder.cpp

Lines changed: 32 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -41,14 +41,20 @@ CommandForwarder::CommandForwarder(
4141
state_value_pub_ =
4242
node_->create_publisher<controller_manager_msgs::msg::InterfaceData>(topic_name_, qos_profile);
4343

44-
rclcpp::NodeOptions node_options;
45-
node_options.clock_type(rcl_clock_type_t::RCL_STEADY_TIME);
46-
evaluation_node_ = std::make_shared<rclcpp_lifecycle::LifecycleNode>(
47-
loaned_command_interface_ptr_->get_underscore_separated_name() + "evaluation_node", namespace_,
48-
node_options, false);
49-
evaluation_pub_ = evaluation_node_->create_publisher<controller_manager_msgs::msg::Evaluation>(
50-
evaluation_topic_name_, 10);
51-
evaluation_identifier_ = loaned_command_interface_ptr_->get_underscore_separated_name();
44+
publish_evaluation_msg_ = evaluation_helper->publish_evaluation_msg();
45+
if (publish_evaluation_msg_)
46+
{
47+
rclcpp::NodeOptions node_options;
48+
node_options.clock_type(rcl_clock_type_t::RCL_STEADY_TIME);
49+
evaluation_node_ = std::make_shared<rclcpp_lifecycle::LifecycleNode>(
50+
loaned_command_interface_ptr_->get_underscore_separated_name() + "evaluation_node",
51+
namespace_, node_options, false);
52+
rclcpp::QoS evaluation_qos_profile(
53+
rclcpp::QoSInitialization::from_rmw(evaluation_helper->get_evaluation_qos_profile()));
54+
evaluation_pub_ = evaluation_node_->create_publisher<controller_manager_msgs::msg::Evaluation>(
55+
evaluation_topic_name_, evaluation_qos_profile);
56+
evaluation_identifier_ = loaned_command_interface_ptr_->get_underscore_separated_name();
57+
}
5258

5359
// TODO(Manuel): We should check if we cannot detect changes to LoanedStateInterface's value and only publish then
5460
timer_ = node_->create_wall_timer(
@@ -136,20 +142,27 @@ void CommandForwarder::publish_value_on_timer()
136142

137143
void CommandForwarder::forward_command(const controller_manager_msgs::msg::InterfaceData & msg)
138144
{
139-
auto receive_time = evaluation_node_->now();
145+
// first get timestamp to be as precise as possible
146+
if (publish_evaluation_msg_)
147+
{
148+
receive_time_ = evaluation_node_->now();
149+
}
140150
//set value before publishing
141151
loaned_command_interface_ptr_->set_value(msg.data);
142152

143-
auto evaluation_msg = std::make_unique<controller_manager_msgs::msg::Evaluation>();
144-
evaluation_msg->receive_stamp = receive_time;
145-
evaluation_msg->receive_time =
146-
static_cast<uint64_t>(evaluation_msg->receive_stamp.sec) * 1'000'000'000ULL +
147-
evaluation_msg->receive_stamp.nanosec;
148-
evaluation_msg->type = evaluation_type_;
149-
evaluation_msg->identifier = evaluation_identifier_;
150-
evaluation_msg->seq = msg.header.seq;
151-
// todo check for QoS to publish immediately and never block to be fast as possible
152-
evaluation_pub_->publish(std::move(evaluation_msg));
153+
if (publish_evaluation_msg_)
154+
{
155+
auto evaluation_msg = std::make_unique<controller_manager_msgs::msg::Evaluation>();
156+
evaluation_msg->receive_stamp = receive_time_;
157+
evaluation_msg->receive_time =
158+
static_cast<uint64_t>(evaluation_msg->receive_stamp.sec) * 1'000'000'000ULL +
159+
evaluation_msg->receive_stamp.nanosec;
160+
evaluation_msg->type = evaluation_type_;
161+
evaluation_msg->identifier = evaluation_identifier_;
162+
evaluation_msg->seq = msg.header.seq;
163+
// todo check for QoS to publish immediately and never block to be fast as possible
164+
evaluation_pub_->publish(std::move(evaluation_msg));
165+
}
153166
}
154167

155168
} // namespace distributed_control

0 commit comments

Comments
 (0)