Skip to content

Commit

Permalink
remove cancel_step
Browse files Browse the repository at this point in the history
  • Loading branch information
domire8 committed Oct 8, 2024
1 parent 44ccd72 commit ecd0a44
Show file tree
Hide file tree
Showing 8 changed files with 7 additions and 23 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,6 @@ class Component : public rclcpp::Node, public ComponentInterface {
void on_execute();

// TODO hide ROS methods
using ComponentInterface::cancel_step;
using ComponentInterface::create_output;
using ComponentInterface::evaluate_periodic_callbacks;
using ComponentInterface::finalize_interfaces;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,11 +93,6 @@ class ComponentInterface {
*/
virtual void on_step_callback();

/**
* @brief Cancel the step timer.
*/
void cancel_step();

/**
* @brief Add a parameter.
* @details This method stores a pointer reference to an existing Parameter object in the local parameter map and
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -266,7 +266,6 @@ class LifecycleComponent : public rclcpp_lifecycle::LifecycleNode, public Compon
bool has_error_;

// TODO hide ROS methods
using ComponentInterface::cancel_step;
using ComponentInterface::create_output;
using ComponentInterface::evaluate_periodic_callbacks;
using ComponentInterface::finalize_interfaces;
Expand Down
2 changes: 1 addition & 1 deletion source/modulo_components/modulo_components/component.py
Original file line number Diff line number Diff line change
Expand Up @@ -103,4 +103,4 @@ def raise_error(self):
"""
super().raise_error()
self.set_predicate("in_error_state", True)
self._cancel_step()
self._finalize_interfaces()
Original file line number Diff line number Diff line change
Expand Up @@ -113,13 +113,6 @@ def on_step_callback(self):
"""
pass

def _cancel_step(self):
"""
Cancel the step timer.
"""
if self.__step_timer:
self.__step_timer.cancel()

def add_parameter(self, parameter: Union[str, sr.Parameter], description: str, read_only=False) -> None:
"""
Add a parameter. This method stores either the name of the attribute corresponding to the parameter object or
Expand Down Expand Up @@ -942,4 +935,6 @@ def _finalize_interfaces(self):
self.__tf_broadcaster = None
self.__static_tf_broadcaster = None
self._predicate_publisher = None
if self.__step_timer:
self.__step_timer.cancel()
self.__step_timer = None
2 changes: 1 addition & 1 deletion source/modulo_components/src/Component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,6 @@ std::shared_ptr<state_representation::ParameterInterface> Component::get_paramet
void Component::raise_error() {
ComponentInterface::raise_error();
this->set_predicate("in_error_state", true);
this->cancel_step();
this->finalize_interfaces();
}
}// namespace modulo_components
9 changes: 3 additions & 6 deletions source/modulo_components/src/ComponentInterface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,12 +73,6 @@ void ComponentInterface::step() {}

void ComponentInterface::on_step_callback() {}

void ComponentInterface::cancel_step() {
if (this->step_timer_ != nullptr) {
this->step_timer_->cancel();
}
}

void ComponentInterface::add_parameter(
const std::shared_ptr<state_representation::ParameterInterface>& parameter, const std::string& description,
bool read_only) {
Expand Down Expand Up @@ -622,6 +616,9 @@ void ComponentInterface::finalize_interfaces() {
this->predicate_publisher_.reset();
this->empty_services_.clear();
this->string_services_.clear();
if (this->step_timer_ != nullptr) {
this->step_timer_->cancel();
}
this->step_timer_.reset();
this->tf_buffer_.reset();
this->tf_listener_.reset();
Expand Down
1 change: 0 additions & 1 deletion source/modulo_controllers/src/BaseControllerInterface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@ BaseControllerInterface::on_configure(const rclcpp_lifecycle::State&) {
add_outputs();

if (predicates_.size()) {
// TODO: topic
predicate_publisher_ =
get_node()->create_publisher<modulo_interfaces::msg::PredicateCollection>("/predicates", qos_);
predicate_message_.node = get_node()->get_fully_qualified_name();
Expand Down

0 comments on commit ecd0a44

Please sign in to comment.