Skip to content

Commit

Permalink
Merge branch 'master' into async_hwif_lifecycle
Browse files Browse the repository at this point in the history
  • Loading branch information
bmagyar authored May 14, 2023
2 parents 1e6555a + 5065d0c commit 38b4ef6
Show file tree
Hide file tree
Showing 10 changed files with 28 additions and 28 deletions.
6 changes: 3 additions & 3 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ repos:

# Python hooks
- repo: https://github.com/asottile/pyupgrade
rev: v3.3.1
rev: v3.4.0
hooks:
- id: pyupgrade
args: [--py36-plus]
Expand All @@ -49,7 +49,7 @@ repos:
args: ["--ignore=D100,D101,D102,D103,D104,D105,D106,D107,D203,D212,D404"]

- repo: https://github.com/psf/black
rev: 23.1.0
rev: 23.3.0
hooks:
- id: black
args: ["--line-length=99"]
Expand Down Expand Up @@ -128,7 +128,7 @@ repos:
# Spellcheck in comments and docs
# skipping of *.svg files is not working...
- repo: https://github.com/codespell-project/codespell
rev: v2.2.2
rev: v2.2.4
hooks:
- id: codespell
args: ['--write-changes']
Expand Down
17 changes: 0 additions & 17 deletions controller_manager/controller_manager/spawner.py
Original file line number Diff line number Diff line change
Expand Up @@ -184,13 +184,6 @@ def main(args=None):
default=10,
type=int,
)
parser.add_argument(
"--log-level",
help="Log level for spawner node",
required=False,
choices=["debug", "info", "warn", "error", "fatal"],
default="info",
)

command_line_args = rclpy.utilities.remove_ros_args(args=sys.argv)[1:]
args = parser.parse_args(command_line_args)
Expand All @@ -200,15 +193,6 @@ def main(args=None):
param_file = args.param_file
controller_type = args.controller_type
controller_manager_timeout = args.controller_manager_timeout
log_level = args.log_level

loglevel_to_severity = {
"debug": rclpy.logging.LoggingSeverity.DEBUG,
"info": rclpy.logging.LoggingSeverity.INFO,
"warn": rclpy.logging.LoggingSeverity.WARN,
"error": rclpy.logging.LoggingSeverity.ERROR,
"fatal": rclpy.logging.LoggingSeverity.FATAL,
}

if param_file and not os.path.isfile(param_file):
raise FileNotFoundError(errno.ENOENT, os.strerror(errno.ENOENT), param_file)
Expand All @@ -218,7 +202,6 @@ def main(args=None):
prefixed_controller_name = controller_namespace + "/" + controller_name

node = Node("spawner_" + controller_name)
rclpy.logging.set_logger_level("spawner_" + controller_name, loglevel_to_severity[log_level])

if not controller_manager_name.startswith("/"):
spawner_namespace = node.get_namespace()
Expand Down
2 changes: 2 additions & 0 deletions doc/index.rst
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
:github_url: https://github.com/ros-controls/ros2_control/blob/|github_branch|/doc/index.rst

.. _ros2_control_framework:

#################
Expand Down
4 changes: 3 additions & 1 deletion hardware_interface/doc/hardware_components_userdoc.rst
Original file line number Diff line number Diff line change
@@ -1,10 +1,12 @@
:github_url: https://github.com/ros-controls/ros2_control/blob/|github_branch|/hardware_interface/doc/hardware_components_userdoc.rst

.. _hardware_components_userdoc:

Hardware Components
-------------------
Hardware components represent abstraction of physical hardware in ros2_control framework.
There are three types of hardware Actuator, Sensor and System.
For details on each type check `Hardware Components description <https://ros-controls.github.io/control.ros.org/getting_started.html#hardware-components>`_.
For details on each type check :ref:`overview_hardware_components` description.

Guidelines and Best Practices
*****************************
Expand Down
2 changes: 2 additions & 0 deletions hardware_interface/doc/mock_components_userdoc.rst
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
:github_url: https://github.com/ros-controls/ros2_control/blob/|github_branch|/hardware_interface/doc/mock_components_userdoc.rst

.. _mock_components_userdoc:

Mock Components
Expand Down
2 changes: 2 additions & 0 deletions hardware_interface/doc/writing_new_hardware_interface.rst
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
:github_url: https://github.com/ros-controls/ros2_control/blob/|github_branch|/hardware_interface/doc/writing_new_hardware_interface.rst

.. _writing_new_hardware_interface:

Writing a new hardware interface
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,5 +33,8 @@ namespace hardware_interface
HARDWARE_INTERFACE_PUBLIC
std::vector<HardwareInfo> parse_control_resources_from_urdf(const std::string & urdf);

HARDWARE_INTERFACE_PUBLIC
bool parse_bool(const std::string & bool_string);

} // namespace hardware_interface
#endif // HARDWARE_INTERFACE__COMPONENT_PARSER_HPP_
7 changes: 6 additions & 1 deletion hardware_interface/src/component_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -224,7 +224,7 @@ std::string parse_data_type_attribute(const tinyxml2::XMLElement * elem)
bool parse_is_async_attribute(const tinyxml2::XMLElement * elem)
{
const tinyxml2::XMLAttribute * attr = elem->FindAttribute(kIsAsyncAttribute);
return attr ? strcasecmp(attr->Value(), "true") == 0 : false;
return attr ? parse_bool(attr->Value()) : false;
}

/// Search XML snippet from URDF for parameters.
Expand Down Expand Up @@ -612,4 +612,9 @@ std::vector<HardwareInfo> parse_control_resources_from_urdf(const std::string &
return hardware_info;
}

bool parse_bool(const std::string & bool_string)
{
return bool_string == "true" || bool_string == "True";
}

} // namespace hardware_interface
11 changes: 5 additions & 6 deletions hardware_interface/src/mock_components/generic_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include <string>
#include <vector>

#include "hardware_interface/component_parser.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "rcutils/logging_macros.h"

Expand Down Expand Up @@ -74,16 +75,15 @@ CallbackReturn GenericSystem::on_init(const hardware_interface::HardwareInfo & i
auto it = info_.hardware_parameters.find("mock_sensor_commands");
if (it != info_.hardware_parameters.end())
{
// TODO(anyone): change this to parse_bool() (see ros2_control#339)
use_mock_sensor_command_interfaces_ = it->second == "true" || it->second == "True";
use_mock_sensor_command_interfaces_ = hardware_interface::parse_bool(it->second);
}
else
{
// check if fake_sensor_commands was set instead and issue warning.
it = info_.hardware_parameters.find("fake_sensor_commands");
if (it != info_.hardware_parameters.end())
{
use_mock_sensor_command_interfaces_ = it->second == "true" || it->second == "True";
use_mock_sensor_command_interfaces_ = hardware_interface::parse_bool(it->second);
RCUTILS_LOG_WARN_NAMED(
"fake_generic_system",
"Parameter 'fake_sensor_commands' has been deprecated from usage. Use"
Expand All @@ -99,8 +99,7 @@ CallbackReturn GenericSystem::on_init(const hardware_interface::HardwareInfo & i
it = info_.hardware_parameters.find("fake_gpio_commands");
if (it != info_.hardware_parameters.end())
{
// TODO(anyone): change this to parse_bool() (see ros2_control#339)
use_fake_gpio_command_interfaces_ = it->second == "true" || it->second == "True";
use_fake_gpio_command_interfaces_ = hardware_interface::parse_bool(it->second);
}
else
{
Expand All @@ -121,7 +120,7 @@ CallbackReturn GenericSystem::on_init(const hardware_interface::HardwareInfo & i
custom_interface_with_following_offset_ = it->second;
}
}
// its extremlly unprobably that std::distance results int this value - therefore default
// it's extremely improbable that std::distance results int this value - therefore default
index_custom_interface_with_following_offset_ = std::numeric_limits<size_t>::max();

// Initialize storage for standard interfaces
Expand Down
2 changes: 2 additions & 0 deletions ros2controlcli/doc/userdoc.rst
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
:github_url: https://github.com/ros-controls/ros2_control/blob/|github_branch|/ros2controlcli/doc/userdoc.rst

.. _ros2controlcli_userdoc:

Command Line Interface
Expand Down

0 comments on commit 38b4ef6

Please sign in to comment.