Skip to content

Commit

Permalink
add helper function to discard lifecycle state that doesn't need any …
Browse files Browse the repository at this point in the history
…action
  • Loading branch information
saikishor committed Aug 26, 2024
1 parent 1e453bc commit 1bab232
Show file tree
Hide file tree
Showing 5 changed files with 40 additions and 20 deletions.
1 change: 1 addition & 0 deletions hardware_interface/include/hardware_interface/actuator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include "hardware_interface/actuator_interface.hpp"
#include "hardware_interface/handle.hpp"
#include "hardware_interface/hardware_info.hpp"
#include "hardware_interface/helpers.hpp"
#include "hardware_interface/types/hardware_interface_return_values.hpp"
#include "hardware_interface/visibility_control.h"
#include "rclcpp/duration.hpp"
Expand Down
32 changes: 32 additions & 0 deletions hardware_interface/include/hardware_interface/helpers.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
// Copyright 2024 PAL Robotics S.L.
//
// 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 HARDWARE_INTERFACE__HELPERS_HPP_
#define HARDWARE_INTERFACE__HELPERS_HPP_

#include <functional>
#include <string>
#include <vector>

namespace hardware_interface
{
constexpr bool lifecycleStateThatRequiresNoAction(const lifecycle_msgs::msg::State::_id_type state)
{
return state == lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN ||
state == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED ||
state == lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED;
}
} // namespace hardware_interface

#endif // HARDWARE_INTERFACE__HELPERS_HPP_
10 changes: 2 additions & 8 deletions hardware_interface/src/actuator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -246,10 +246,7 @@ return_type Actuator::read(const rclcpp::Time & time, const rclcpp::Duration & p
impl_->get_name().c_str());
return return_type::OK;
}
if (
impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN ||
impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED ||
impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED)
if (lifecycleStateThatRequiresNoAction(impl_->get_lifecycle_state().id()))
{
return return_type::OK;
}
Expand Down Expand Up @@ -277,10 +274,7 @@ return_type Actuator::write(const rclcpp::Time & time, const rclcpp::Duration &
impl_->get_name().c_str());
return return_type::OK;
}
if (
impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN ||
impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED ||
impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED)
if (lifecycleStateThatRequiresNoAction(impl_->get_lifecycle_state().id()))
{
return return_type::OK;
}
Expand Down
6 changes: 2 additions & 4 deletions hardware_interface/src/sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@

#include "hardware_interface/handle.hpp"
#include "hardware_interface/hardware_info.hpp"
#include "hardware_interface/helpers.hpp"
#include "hardware_interface/sensor_interface.hpp"
#include "hardware_interface/types/hardware_interface_return_values.hpp"
#include "hardware_interface/types/lifecycle_state_names.hpp"
Expand Down Expand Up @@ -224,10 +225,7 @@ return_type Sensor::read(const rclcpp::Time & time, const rclcpp::Duration & per
impl_->get_name().c_str());
return return_type::OK;
}
if (
impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN ||
impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED ||
impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED)
if (lifecycleStateThatRequiresNoAction(impl_->get_lifecycle_state().id()))
{
return return_type::OK;
}
Expand Down
11 changes: 3 additions & 8 deletions hardware_interface/src/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@

#include "hardware_interface/handle.hpp"
#include "hardware_interface/hardware_info.hpp"
#include "hardware_interface/helpers.hpp"
#include "hardware_interface/system_interface.hpp"
#include "hardware_interface/types/hardware_interface_return_values.hpp"
#include "hardware_interface/types/lifecycle_state_names.hpp"
Expand Down Expand Up @@ -242,10 +243,7 @@ return_type System::read(const rclcpp::Time & time, const rclcpp::Duration & per
impl_->get_name().c_str());
return return_type::OK;
}
if (
impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN ||
impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED ||
impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED)
if (lifecycleStateThatRequiresNoAction(impl_->get_lifecycle_state().id()))
{
return return_type::OK;
}
Expand Down Expand Up @@ -273,10 +271,7 @@ return_type System::write(const rclcpp::Time & time, const rclcpp::Duration & pe
impl_->get_name().c_str());
return return_type::OK;
}
if (
impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN ||
impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED ||
impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED)
if (lifecycleStateThatRequiresNoAction(impl_->get_lifecycle_state().id()))
{
return return_type::OK;
}
Expand Down

0 comments on commit 1bab232

Please sign in to comment.