Skip to content

Commit 6f3740e

Browse files
committed
first rough adaption of published massage with header
changes for command side, publishing missing add time and publishing of when command is received
1 parent 3ad3fd3 commit 6f3740e

File tree

9 files changed

+78
-26
lines changed

9 files changed

+78
-26
lines changed

controller_manager_msgs/CMakeLists.txt

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,9 +9,12 @@ find_package(rosidl_default_generators REQUIRED)
99
set(msg_files
1010
msg/ControllerState.msg
1111
msg/ChainConnection.msg
12+
msg/Evaluation.msg
1213
msg/HandleName.msg
1314
msg/HardwareComponentState.msg
1415
msg/HardwareInterface.msg
16+
msg/Header.msg
17+
msg/InterfaceData.msg
1518
msg/PublisherDescription.msg
1619
)
1720
set(srv_files
Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
string identifier
2+
string type
3+
uint32 seq
4+
uint64 receive_time
5+
builtin_interfaces/Time receive_stamp
Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
uint32 seq
Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
controller_manager_msgs/Header header
2+
float64 data

hardware_interface/include/hardware_interface/distributed_control_interface/command_forwarder.hpp

Lines changed: 11 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,11 @@
1212

1313
#include "controller_manager_msgs/msg/publisher_description.hpp"
1414

15+
#include "controller_manager_msgs/msg/evaluation.hpp"
16+
#include "controller_manager_msgs/msg/interface_data.hpp"
1517
#include "rclcpp/rclcpp.hpp"
1618
#include "rclcpp_lifecycle/lifecycle_node.hpp"
1719
#include "rclcpp_lifecycle/state.hpp"
18-
#include "std_msgs/msg/float64.hpp"
1920

2021
namespace distributed_control
2122
{
@@ -52,18 +53,24 @@ class CommandForwarder final
5253

5354
private:
5455
void publish_value_on_timer();
55-
void forward_command(const std_msgs::msg::Float64 & msg);
56+
void forward_command(const controller_manager_msgs::msg::InterfaceData & msg);
5657

5758
std::unique_ptr<hardware_interface::LoanedCommandInterface> loaned_command_interface_ptr_;
5859
const std::string namespace_;
5960
const std::chrono::milliseconds period_in_ms_;
6061

6162
const std::string topic_name_;
63+
const std::string evaluation_topic_name_;
6264
std::string subscription_topic_name_;
6365
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node_;
64-
rclcpp::Publisher<std_msgs::msg::Float64>::SharedPtr state_value_pub_;
65-
rclcpp::Subscription<std_msgs::msg::Float64>::SharedPtr command_subscription_;
66+
rclcpp::Publisher<controller_manager_msgs::msg::InterfaceData>::SharedPtr state_value_pub_;
67+
rclcpp::Subscription<controller_manager_msgs::msg::InterfaceData>::SharedPtr
68+
command_subscription_;
6669
rclcpp::TimerBase::SharedPtr timer_;
70+
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> evaluation_node_;
71+
rclcpp::Publisher<controller_manager_msgs::msg::Evaluation>::SharedPtr evaluation_pub_;
72+
const std::string evaluation_type_ = "commandInterface";
73+
std::string evaluation_identifier_;
6774
};
6875

6976
} // namespace distributed_control

hardware_interface/include/hardware_interface/distributed_control_interface/state_publisher.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -10,10 +10,10 @@
1010

1111
#include "controller_manager_msgs/msg/publisher_description.hpp"
1212

13+
#include "controller_manager_msgs/msg/interface_data.hpp"
1314
#include "rclcpp/rclcpp.hpp"
1415
#include "rclcpp_lifecycle/lifecycle_node.hpp"
1516
#include "rclcpp_lifecycle/state.hpp"
16-
#include "std_msgs/msg/float64.hpp"
1717

1818
namespace distributed_control
1919
{
@@ -54,8 +54,9 @@ class StatePublisher final
5454

5555
const std::string topic_name_;
5656
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node_;
57-
rclcpp::Publisher<std_msgs::msg::Float64>::SharedPtr state_value_pub_;
57+
rclcpp::Publisher<controller_manager_msgs::msg::InterfaceData>::SharedPtr state_value_pub_;
5858
rclcpp::TimerBase::SharedPtr timer_;
59+
uint32_t seq_number_ = 0;
5960
};
6061

6162
} // namespace distributed_control

hardware_interface/include/hardware_interface/handle.hpp

Lines changed: 16 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
#include "hardware_interface/macros.hpp"
2424
#include "hardware_interface/visibility_control.h"
2525

26+
#include "controller_manager_msgs/msg/interface_data.hpp"
2627
#include "rclcpp/rclcpp.hpp"
2728
#include "rclcpp_lifecycle/lifecycle_node.hpp"
2829
#include "std_msgs/msg/float64.hpp"
@@ -203,6 +204,7 @@ class DistributedReadOnlyHandle : public ReadOnlyHandle
203204
if (!node_.get())
204205
{
205206
rclcpp::NodeOptions node_options;
207+
node_options.clock_type(rcl_clock_type_t::RCL_STEADY_TIME);
206208
node_ = std::make_shared<rclcpp_lifecycle::LifecycleNode>(
207209
get_underscore_separated_name() + "_state_interface_subscriber", namespace_, node_options,
208210
false);
@@ -212,7 +214,7 @@ class DistributedReadOnlyHandle : public ReadOnlyHandle
212214
rclcpp::QoS qos_profile(
213215
rclcpp::QoSInitialization::from_rmw(evaluation_helper->get_qos_profile()));
214216
// subscribe to topic provided by StatePublisher
215-
state_value_sub_ = node_->create_subscription<std_msgs::msg::Float64>(
217+
state_value_sub_ = node_->create_subscription<controller_manager_msgs::msg::InterfaceData>(
216218
get_value_topic_name_, qos_profile,
217219
std::bind(&DistributedReadOnlyHandle::get_value_cb, this, std::placeholders::_1));
218220
}
@@ -256,7 +258,7 @@ class DistributedReadOnlyHandle : public ReadOnlyHandle
256258
}
257259

258260
protected:
259-
void get_value_cb(const std_msgs::msg::Float64 & msg)
261+
void get_value_cb(const controller_manager_msgs::msg::InterfaceData & msg)
260262
{
261263
value_ = msg.data;
262264
RCLCPP_DEBUG_STREAM(node_->get_logger(), "Receiving:[" << value_ << "].");
@@ -268,7 +270,7 @@ class DistributedReadOnlyHandle : public ReadOnlyHandle
268270
// the namespace the actual StateInterface we subscribe to is in.
269271
// We need this to create unique names for the StateInterface.
270272
std::string interface_namespace_;
271-
rclcpp::Subscription<std_msgs::msg::Float64>::SharedPtr state_value_sub_;
273+
rclcpp::Subscription<controller_manager_msgs::msg::InterfaceData>::SharedPtr state_value_sub_;
272274
double value_;
273275
};
274276

@@ -354,6 +356,7 @@ class DistributedReadWriteHandle : public ReadWriteHandle
354356
if (!node_.get())
355357
{
356358
rclcpp::NodeOptions node_options;
359+
node_options.clock_type(rcl_clock_type_t::RCL_STEADY_TIME);
357360
node_ = std::make_shared<rclcpp_lifecycle::LifecycleNode>(
358361
get_underscore_separated_name() + "_distributed_command_interface", namespace_,
359362
node_options, false);
@@ -363,13 +366,13 @@ class DistributedReadWriteHandle : public ReadWriteHandle
363366
rclcpp::QoS qos_profile(
364367
rclcpp::QoSInitialization::from_rmw(evaluation_helper->get_qos_profile()));
365368
// subscribe to topic provided by CommandForwarder
366-
command_value_sub_ = node_->create_subscription<std_msgs::msg::Float64>(
369+
command_value_sub_ = node_->create_subscription<controller_manager_msgs::msg::InterfaceData>(
367370
get_value_topic_name_, qos_profile,
368371
std::bind(&DistributedReadWriteHandle::get_value_cb, this, std::placeholders::_1));
369372

370373
// create publisher so that we can forward the commands
371-
command_value_pub_ =
372-
node_->create_publisher<std_msgs::msg::Float64>(forward_command_topic_name_, qos_profile);
374+
command_value_pub_ = node_->create_publisher<controller_manager_msgs::msg::InterfaceData>(
375+
forward_command_topic_name_, qos_profile);
373376
}
374377

375378
explicit DistributedReadWriteHandle(const std::string & interface_name)
@@ -410,19 +413,20 @@ class DistributedReadWriteHandle : public ReadWriteHandle
410413

411414
void set_value(double value) override
412415
{
413-
auto msg = std::make_unique<std_msgs::msg::Float64>();
416+
auto msg = std::make_unique<controller_manager_msgs::msg::InterfaceData>();
414417
msg->data = value;
418+
msg->header.seq = seq_number_;
419+
++seq_number_;
415420

416421
RCLCPP_DEBUG(node_->get_logger(), "DistributedCommandInterface Publishing: '%.7lf'", msg->data);
417-
std::flush(std::cout);
418422

419423
command_value_pub_->publish(std::move(msg));
420424
}
421425

422426
std::string forward_command_topic_name() const { return forward_command_topic_name_; }
423427

424428
protected:
425-
void get_value_cb(const std_msgs::msg::Float64 & msg)
429+
void get_value_cb(const controller_manager_msgs::msg::InterfaceData & msg)
426430
{
427431
value_ = msg.data;
428432
RCLCPP_DEBUG_STREAM(
@@ -435,10 +439,11 @@ class DistributedReadWriteHandle : public ReadWriteHandle
435439
// the namespace the actual CommandInterface we subscribe to is in.
436440
// We need this to create unique names for the CommandInterface.
437441
std::string interface_namespace_;
438-
rclcpp::Subscription<std_msgs::msg::Float64>::SharedPtr command_value_sub_;
442+
rclcpp::Subscription<controller_manager_msgs::msg::InterfaceData>::SharedPtr command_value_sub_;
439443
std::string forward_command_topic_name_;
440-
rclcpp::Publisher<std_msgs::msg::Float64>::SharedPtr command_value_pub_;
444+
rclcpp::Publisher<controller_manager_msgs::msg::InterfaceData>::SharedPtr command_value_pub_;
441445
double value_;
446+
uint_fast32_t seq_number_ = 0;
442447
};
443448

444449
class DistributedCommandInterface : public DistributedReadWriteHandle

hardware_interface/src/hardware_interface/distributed_control_interface/command_forwarder.cpp

Lines changed: 30 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -21,12 +21,15 @@ CommandForwarder::CommandForwarder(
2121
namespace_(ns),
2222
period_in_ms_(period_in_ms),
2323
node_(node),
24-
topic_name_(loaned_command_interface_ptr_->get_underscore_separated_name() + "_command_state")
24+
topic_name_(loaned_command_interface_ptr_->get_underscore_separated_name() + "_command_state"),
25+
evaluation_topic_name_(
26+
loaned_command_interface_ptr_->get_underscore_separated_name() + "_EVALUATION")
2527
{
2628
// if we did not get a node passed, we create one ourselves
2729
if (!node_.get())
2830
{
2931
rclcpp::NodeOptions node_options;
32+
node_options.clock_type(rcl_clock_type_t::RCL_STEADY_TIME);
3033
node_ = std::make_shared<rclcpp_lifecycle::LifecycleNode>(
3134
loaned_command_interface_ptr_->get_underscore_separated_name() + "_command_forwarder",
3235
namespace_, node_options, false);
@@ -35,7 +38,18 @@ CommandForwarder::CommandForwarder(
3538
auto evaluation_helper = evaluation_helper::Evaluation_Helper::get_instance();
3639
rclcpp::QoS qos_profile(
3740
rclcpp::QoSInitialization::from_rmw(evaluation_helper->get_qos_profile()));
38-
state_value_pub_ = node_->create_publisher<std_msgs::msg::Float64>(topic_name_, qos_profile);
41+
state_value_pub_ =
42+
node_->create_publisher<controller_manager_msgs::msg::InterfaceData>(topic_name_, qos_profile);
43+
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();
52+
3953
// TODO(Manuel): We should check if we cannot detect changes to LoanedStateInterface's value and only publish then
4054
timer_ = node_->create_wall_timer(
4155
period_in_ms_, std::bind(&CommandForwarder::publish_value_on_timer, this));
@@ -96,15 +110,15 @@ void CommandForwarder::subscribe_to_command_publisher(const std::string & topic_
96110
rclcpp::QoS qos_profile(
97111
rclcpp::QoSInitialization::from_rmw(evaluation_helper->get_qos_profile()));
98112
subscription_topic_name_ = topic_name;
99-
command_subscription_ = node_->create_subscription<std_msgs::msg::Float64>(
113+
command_subscription_ = node_->create_subscription<controller_manager_msgs::msg::InterfaceData>(
100114
subscription_topic_name_, qos_profile,
101115
std::bind(&CommandForwarder::forward_command, this, std::placeholders::_1));
102116
}
103117

104118
void CommandForwarder::publish_value_on_timer()
105119
{
106120
// Todo(Manuel) create custom msg and return success or failure not just nan.
107-
auto msg = std::make_unique<std_msgs::msg::Float64>();
121+
auto msg = std::make_unique<controller_manager_msgs::msg::InterfaceData>();
108122
try
109123
{
110124
msg->data = loaned_command_interface_ptr_->get_value();
@@ -114,15 +128,25 @@ void CommandForwarder::publish_value_on_timer()
114128
msg->data = std::numeric_limits<double>::quiet_NaN();
115129
}
116130
RCLCPP_DEBUG(node_->get_logger(), "Publishing: '%.7lf'", msg->data);
117-
std::flush(std::cout);
118131

119132
// Put the message into a queue to be processed by the middleware.
120133
// This call is non-blocking.
121134
state_value_pub_->publish(std::move(msg));
122135
}
123136

124-
void CommandForwarder::forward_command(const std_msgs::msg::Float64 & msg)
137+
void CommandForwarder::forward_command(const controller_manager_msgs::msg::InterfaceData & msg)
125138
{
139+
auto evaluation_msg = std::make_unique<controller_manager_msgs::msg::Evaluation>();
140+
evaluation_msg->receive_stamp = evaluation_node_->now();
141+
evaluation_msg->receive_time =
142+
static_cast<uint64_t>(evaluation_msg->receive_stamp.sec) * 1'000'000'000ULL +
143+
evaluation_msg->receive_stamp.nanosec;
144+
evaluation_msg->type = evaluation_type_;
145+
evaluation_msg->identifier = evaluation_identifier_;
146+
evaluation_msg->seq = msg.header.seq;
147+
// todo check for QoS to publish immediately and never block to be fast as possible
148+
evaluation_pub_->publish(std::move(evaluation_msg));
149+
126150
loaned_command_interface_ptr_->set_value(msg.data);
127151
}
128152

hardware_interface/src/hardware_interface/distributed_control_interface/state_publisher.cpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -27,15 +27,18 @@ StatePublisher::StatePublisher(
2727
if (!node_.get())
2828
{
2929
rclcpp::NodeOptions node_options;
30+
node_options.clock_type(rcl_clock_type_t::RCL_STEADY_TIME);
3031
node_ = std::make_shared<rclcpp_lifecycle::LifecycleNode>(
3132
loaned_state_interface_ptr_->get_underscore_separated_name() + "_state_publisher", namespace_,
3233
node_options, false);
3334
}
3435

3536
auto evaluation_helper = evaluation_helper::Evaluation_Helper::get_instance();
37+
3638
rclcpp::QoS qos_profile(
3739
rclcpp::QoSInitialization::from_rmw(evaluation_helper->get_qos_profile()));
38-
state_value_pub_ = node_->create_publisher<std_msgs::msg::Float64>(topic_name_, qos_profile);
40+
state_value_pub_ =
41+
node_->create_publisher<controller_manager_msgs::msg::InterfaceData>(topic_name_, qos_profile);
3942
// TODO(Manuel): We should check if we cannot detect changes to LoanedStateInterface's value and only publish then
4043
timer_ = node_->create_wall_timer(
4144
period_in_ms_, std::bind(&StatePublisher::publish_value_on_timer, this));
@@ -91,7 +94,7 @@ StatePublisher::create_publisher_description_msg() const
9194

9295
void StatePublisher::publish_value_on_timer()
9396
{
94-
auto msg = std::make_unique<std_msgs::msg::Float64>();
97+
auto msg = std::make_unique<controller_manager_msgs::msg::InterfaceData>();
9598
try
9699
{
97100
msg->data = loaned_state_interface_ptr_->get_value();
@@ -103,10 +106,11 @@ void StatePublisher::publish_value_on_timer()
103106
msg->data = std::numeric_limits<double>::quiet_NaN();
104107
}
105108
RCLCPP_DEBUG(node_->get_logger(), "Publishing: '%.7lf'", msg->data);
106-
std::flush(std::cout);
107109

108110
// Put the message into a queue to be processed by the middleware.
109111
// This call is non-blocking.
112+
msg->header.seq = seq_number_;
113+
++seq_number_;
110114
state_value_pub_->publish(std::move(msg));
111115
}
112116

0 commit comments

Comments
 (0)