-
Notifications
You must be signed in to change notification settings - Fork 19
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 reference timeout parameter to controllers templates #111
base: master
Are you sure you want to change the base?
Changes from all commits
df36359
0cef88d
62ec6f3
8b5c1c9
77e1b53
27014c9
64c8f1d
e2cc41e
3f27a6e
524e334
508ce0e
40aef82
72605dc
c02dd31
0fb82f6
74b4d11
9692b17
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 |
---|---|---|
@@ -1,4 +1,4 @@ | ||
// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) | ||
// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
|
@@ -41,8 +41,10 @@ using ControllerReferenceMsg = dummy_package_namespace::DummyClassName::Controll | |
|
||
// called from RT control loop | ||
void reset_controller_reference_msg( | ||
const std::shared_ptr<ControllerReferenceMsg> & msg, const std::vector<std::string> & joint_names) | ||
const std::shared_ptr<ControllerReferenceMsg> & msg, const std::vector<std::string> & joint_names, | ||
const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node) | ||
{ | ||
msg->header.stamp = node->now(); | ||
msg->joint_names = joint_names; | ||
msg->displacements.resize(joint_names.size(), std::numeric_limits<double>::quiet_NaN()); | ||
msg->velocities.resize(joint_names.size(), std::numeric_limits<double>::quiet_NaN()); | ||
|
@@ -93,13 +95,15 @@ controller_interface::CallbackReturn DummyClassName::on_configure( | |
subscribers_qos.keep_last(1); | ||
subscribers_qos.best_effort(); | ||
|
||
ref_timeout_ = rclcpp::Duration::from_seconds(params_.reference_timeout); | ||
|
||
// Reference Subscriber | ||
ref_subscriber_ = get_node()->create_subscription<ControllerReferenceMsg>( | ||
"~/reference", subscribers_qos, | ||
std::bind(&DummyClassName::reference_callback, this, std::placeholders::_1)); | ||
|
||
std::shared_ptr<ControllerReferenceMsg> msg = std::make_shared<ControllerReferenceMsg>(); | ||
reset_controller_reference_msg(msg, params_.joints); | ||
reset_controller_reference_msg(msg, params_.joints, get_node()); | ||
input_ref_.writeFromNonRT(msg); | ||
|
||
auto set_slow_mode_service_callback = | ||
|
@@ -139,6 +143,30 @@ controller_interface::CallbackReturn DummyClassName::on_configure( | |
return controller_interface::CallbackReturn::SUCCESS; | ||
} | ||
|
||
void DummyClassName::reference_callback(const std::shared_ptr<ControllerReferenceMsg> msg) | ||
{ | ||
const auto age_of_last_command = get_node()->now() - msg->header.stamp; | ||
if (msg->joint_names.size() == params_.joints.size()) { | ||
if (ref_timeout_ == rclcpp::Duration::from_seconds(0) || age_of_last_command <= ref_timeout_) { | ||
input_ref_.writeFromNonRT(msg); | ||
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. Should we not have here default value of the header is timestamp is "0"? 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. you are referring to this handling of case if header.stamp ==0 right? this is included in the improvements from mecanum PR, you can see the line in the below link, should i also implement this in this ref_timeout PR? |
||
} else { | ||
RCLCPP_ERROR( | ||
get_node()->get_logger(), | ||
"Received message has timestamp %.10f older for %.10f which " | ||
"is more then allowed timeout " | ||
"(%.4f).", | ||
rclcpp::Time(msg->header.stamp).seconds(), age_of_last_command.seconds(), | ||
ref_timeout_.seconds()); | ||
reset_controller_reference_msg(msg, params_.joints, get_node()); | ||
} | ||
} else { | ||
RCLCPP_ERROR( | ||
get_node()->get_logger(), | ||
"Received %zu , but expected %zu joints in command. Ignoring message.", | ||
msg->joint_names.size(), params_.joints.size()); | ||
} | ||
} | ||
|
||
controller_interface::InterfaceConfiguration DummyClassName::command_interface_configuration() const | ||
{ | ||
controller_interface::InterfaceConfiguration command_interfaces_config; | ||
|
@@ -165,18 +193,6 @@ controller_interface::InterfaceConfiguration DummyClassName::state_interface_con | |
return state_interfaces_config; | ||
} | ||
|
||
void DummyClassName::reference_callback(const std::shared_ptr<ControllerReferenceMsg> msg) | ||
{ | ||
if (msg->joint_names.size() == params_.joints.size()) { | ||
input_ref_.writeFromNonRT(msg); | ||
} else { | ||
RCLCPP_ERROR( | ||
get_node()->get_logger(), | ||
"Received %zu , but expected %zu joints in command. Ignoring message.", | ||
msg->joint_names.size(), params_.joints.size()); | ||
} | ||
} | ||
|
||
std::vector<hardware_interface::CommandInterface> DummyClassName::on_export_reference_interfaces() | ||
{ | ||
reference_interfaces_.resize(state_joints_.size(), std::numeric_limits<double>::quiet_NaN()); | ||
|
@@ -203,7 +219,7 @@ controller_interface::CallbackReturn DummyClassName::on_activate( | |
const rclcpp_lifecycle::State & /*previous_state*/) | ||
{ | ||
// Set default value in command | ||
reset_controller_reference_msg(*(input_ref_.readFromRT()), state_joints_); | ||
reset_controller_reference_msg(*(input_ref_.readFromRT()), state_joints_, get_node()); | ||
|
||
return controller_interface::CallbackReturn::SUCCESS; | ||
} | ||
|
@@ -222,14 +238,32 @@ controller_interface::CallbackReturn DummyClassName::on_deactivate( | |
controller_interface::return_type DummyClassName::update_reference_from_subscribers() | ||
{ | ||
auto current_ref = input_ref_.readFromRT(); | ||
const auto age_of_last_command = get_node()->now() - (*current_ref)->header.stamp; | ||
|
||
// TODO(anyone): depending on number of interfaces, use definitions, e.g., `CMD_MY_ITFS`, | ||
// instead of a loop | ||
for (size_t i = 0; i < reference_interfaces_.size(); ++i) { | ||
if (!std::isnan((*current_ref)->displacements[i])) { | ||
reference_interfaces_[i] = (*current_ref)->displacements[i]; | ||
// send message only if there is no timeout | ||
if (age_of_last_command <= ref_timeout_ || ref_timeout_ == rclcpp::Duration::from_seconds(0)) { | ||
if (!std::isnan((*current_ref)->displacements[i])) { | ||
if (*(control_mode_.readFromRT()) == control_mode_type::SLOW) { | ||
(*current_ref)->displacements[i] /= 2; | ||
} | ||
reference_interfaces_[i] = (*current_ref)->displacements[i]; | ||
if (ref_timeout_ == rclcpp::Duration::from_seconds(0)) { | ||
(*current_ref)->displacements[i] = std::numeric_limits<double>::quiet_NaN(); | ||
(*current_ref)->velocities[i] = std::numeric_limits<double>::quiet_NaN(); | ||
(*current_ref)->duration = std::numeric_limits<double>::quiet_NaN(); | ||
} | ||
} | ||
} else { | ||
if (!std::isnan((*current_ref)->displacements[i])) { | ||
reference_interfaces_[i] = 0.0; | ||
|
||
(*current_ref)->displacements[i] = std::numeric_limits<double>::quiet_NaN(); | ||
(*current_ref)->displacements[i] = std::numeric_limits<double>::quiet_NaN(); | ||
(*current_ref)->velocities[i] = std::numeric_limits<double>::quiet_NaN(); | ||
(*current_ref)->duration = std::numeric_limits<double>::quiet_NaN(); | ||
} | ||
} | ||
} | ||
return controller_interface::return_type::OK; | ||
|
@@ -238,16 +272,22 @@ controller_interface::return_type DummyClassName::update_reference_from_subscrib | |
controller_interface::return_type DummyClassName::update_and_write_commands( | ||
const rclcpp::Time & time, const rclcpp::Duration & /*period*/) | ||
{ | ||
auto current_ref = input_ref_.readFromRT(); | ||
// TODO(anyone): depending on number of interfaces, use definitions, e.g., `CMD_MY_ITFS`, | ||
// instead of a loop | ||
for (size_t i = 0; i < command_interfaces_.size(); ++i) { | ||
// send message only if there is no timeout | ||
if (!std::isnan(reference_interfaces_[i])) { | ||
if (*(control_mode_.readFromRT()) == control_mode_type::SLOW) { | ||
reference_interfaces_[i] /= 2; | ||
} | ||
command_interfaces_[i].set_value(reference_interfaces_[i]); | ||
|
||
reference_interfaces_[i] = std::numeric_limits<double>::quiet_NaN(); | ||
if (ref_timeout_ == rclcpp::Duration::from_seconds(0)) { | ||
reference_interfaces_[i] = std::numeric_limits<double>::quiet_NaN(); | ||
(*current_ref)->displacements[i] = std::numeric_limits<double>::quiet_NaN(); | ||
(*current_ref)->velocities[i] = std::numeric_limits<double>::quiet_NaN(); | ||
(*current_ref)->duration = std::numeric_limits<double>::quiet_NaN(); | ||
} | ||
} | ||
} | ||
|
||
|
@@ -258,6 +298,9 @@ controller_interface::return_type DummyClassName::update_and_write_commands( | |
state_publisher_->unlockAndPublish(); | ||
} | ||
|
||
for (size_t i = 0; i < reference_interfaces_.size(); ++i) { | ||
reference_interfaces_[i] = std::numeric_limits<double>::quiet_NaN(); | ||
} | ||
return controller_interface::return_type::OK; | ||
} | ||
|
||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,4 +1,4 @@ | ||
// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) | ||
// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
|
@@ -41,8 +41,10 @@ using ControllerReferenceMsg = dummy_package_namespace::DummyClassName::Controll | |
|
||
// called from RT control loop | ||
void reset_controller_reference_msg( | ||
std::shared_ptr<ControllerReferenceMsg> & msg, const std::vector<std::string> & joint_names) | ||
const std::shared_ptr<ControllerReferenceMsg> & msg, const std::vector<std::string> & joint_names, | ||
const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node) | ||
{ | ||
msg->header.stamp = node->now(); | ||
msg->joint_names = joint_names; | ||
msg->displacements.resize(joint_names.size(), std::numeric_limits<double>::quiet_NaN()); | ||
msg->velocities.resize(joint_names.size(), std::numeric_limits<double>::quiet_NaN()); | ||
|
@@ -93,13 +95,15 @@ controller_interface::CallbackReturn DummyClassName::on_configure( | |
subscribers_qos.keep_last(1); | ||
subscribers_qos.best_effort(); | ||
|
||
ref_timeout_ = rclcpp::Duration::from_seconds(params_.reference_timeout); | ||
|
||
// Reference Subscriber | ||
ref_subscriber_ = get_node()->create_subscription<ControllerReferenceMsg>( | ||
"~/reference", subscribers_qos, | ||
std::bind(&DummyClassName::reference_callback, this, std::placeholders::_1)); | ||
|
||
std::shared_ptr<ControllerReferenceMsg> msg = std::make_shared<ControllerReferenceMsg>(); | ||
reset_controller_reference_msg(msg, params_.joints); | ||
reset_controller_reference_msg(msg, params_.joints, get_node()); | ||
input_ref_.writeFromNonRT(msg); | ||
|
||
auto set_slow_mode_service_callback = | ||
|
@@ -141,8 +145,20 @@ controller_interface::CallbackReturn DummyClassName::on_configure( | |
|
||
void DummyClassName::reference_callback(const std::shared_ptr<ControllerReferenceMsg> msg) | ||
{ | ||
const auto age_of_last_command = get_node()->now() - msg->header.stamp; | ||
if (msg->joint_names.size() == params_.joints.size()) { | ||
input_ref_.writeFromNonRT(msg); | ||
if (ref_timeout_ == rclcpp::Duration::from_seconds(0) || age_of_last_command <= ref_timeout_) { | ||
input_ref_.writeFromNonRT(msg); | ||
} else { | ||
RCLCPP_ERROR( | ||
get_node()->get_logger(), | ||
"Received message has timestamp %.10f older for %.10f which " | ||
"is more then allowed timeout " | ||
"(%.4f).", | ||
rclcpp::Time(msg->header.stamp).seconds(), age_of_last_command.seconds(), | ||
ref_timeout_.seconds()); | ||
reset_controller_reference_msg(msg, params_.joints, get_node()); | ||
} | ||
} else { | ||
RCLCPP_ERROR( | ||
get_node()->get_logger(), | ||
|
@@ -185,7 +201,7 @@ controller_interface::CallbackReturn DummyClassName::on_activate( | |
// `controller_interface::get_ordered_interfaces` helper function | ||
|
||
// Set default value in command | ||
reset_controller_reference_msg(*(input_ref_.readFromRT)(), params_.joints); | ||
reset_controller_reference_msg(*(input_ref_.readFromRT)(), params_.joints, get_node()); | ||
|
||
return controller_interface::CallbackReturn::SUCCESS; | ||
} | ||
|
@@ -205,17 +221,29 @@ controller_interface::return_type DummyClassName::update( | |
const rclcpp::Time & time, const rclcpp::Duration & /*period*/) | ||
{ | ||
auto current_ref = input_ref_.readFromRT(); | ||
const auto age_of_last_command = get_node()->now() - (*current_ref)->header.stamp; | ||
|
||
// TODO(anyone): depending on number of interfaces, use definitions, e.g., `CMD_MY_ITFS`, | ||
// instead of a loop | ||
for (size_t i = 0; i < command_interfaces_.size(); ++i) { | ||
if (!std::isnan((*current_ref)->displacements[i])) { | ||
if (*(control_mode_.readFromRT()) == control_mode_type::SLOW) { | ||
(*current_ref)->displacements[i] /= 2; | ||
// send message only if there is no timeout | ||
if (age_of_last_command <= ref_timeout_ || ref_timeout_ == rclcpp::Duration::from_seconds(0)) { | ||
if (!std::isnan((*current_ref)->displacements[i])) { | ||
if (*(control_mode_.readFromRT()) == control_mode_type::SLOW) { | ||
(*current_ref)->displacements[i] /= 2; | ||
} | ||
command_interfaces_[i].set_value((*current_ref)->displacements[i]); | ||
if (ref_timeout_ == rclcpp::Duration::from_seconds(0)) { | ||
(*current_ref)->displacements[i] = std::numeric_limits<double>::quiet_NaN(); | ||
(*current_ref)->velocities[i] = std::numeric_limits<double>::quiet_NaN(); | ||
(*current_ref)->duration = std::numeric_limits<double>::quiet_NaN(); | ||
} | ||
} | ||
command_interfaces_[i].set_value((*current_ref)->displacements[i]); | ||
|
||
} else { | ||
command_interfaces_[i].set_value(0.0); | ||
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. here under is missing resetting of refrence interfaces... 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. this is standard controller and in my understanding we dont have reference_interfaces in standard controller. Please correct me if i am wrong |
||
(*current_ref)->displacements[i] = std::numeric_limits<double>::quiet_NaN(); | ||
(*current_ref)->velocities[i] = std::numeric_limits<double>::quiet_NaN(); | ||
(*current_ref)->duration = std::numeric_limits<double>::quiet_NaN(); | ||
} | ||
} | ||
|
||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -5,3 +5,5 @@ test_dummy_controller: | |
- joint1 | ||
|
||
interface_name: acceleration | ||
|
||
reference_timeout: 0.1 |
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -7,3 +7,5 @@ test_dummy_controller: | |
|
||
state_joints: | ||
- joint1state | ||
|
||
reference_timeout: 0.1 |
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.
saw that ref_callback is called in different order in standard and chainable controller, hence adjusting it to be consistent with standard controller
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.
in the chainable controller,
this callback is not used at all. I mean, you can call it, but nothing will happen.
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.
sorry for the confusion i should have written "ref_callback is defined in different order in standard and chain-able controller classes, hence adjusting it to be consistent with standard controller"
its trivial change, just changed the order