Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions joint_trajectory_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ generate_parameter_library(joint_trajectory_controller_parameters
add_library(joint_trajectory_controller SHARED
src/joint_trajectory_controller.cpp
src/trajectory.cpp
src/validate_jtc_parameters.cpp
)
target_compile_features(joint_trajectory_controller PUBLIC cxx_std_17)
if(WIN32)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,79 +24,26 @@

namespace joint_trajectory_controller
{
tl::expected<void, std::string> command_interface_type_combinations(
rclcpp::Parameter const & parameter)
{
auto const & interface_types = parameter.as_string_array();

// Check if command interfaces combination is valid. Valid combinations are:
// 1. effort
// 2. velocity
// 3. position [velocity, [acceleration]]
// 4. position, effort

if (
rsl::contains<std::vector<std::string>>(interface_types, "velocity") &&
interface_types.size() > 1 &&
!rsl::contains<std::vector<std::string>>(interface_types, "position"))
{
return tl::make_unexpected(
"'velocity' command interface can be used either alone or 'position' "
"command interface has to be present");
}

if (
rsl::contains<std::vector<std::string>>(interface_types, "acceleration") &&
(!rsl::contains<std::vector<std::string>>(interface_types, "velocity") &&
!rsl::contains<std::vector<std::string>>(interface_types, "position")))
{
return tl::make_unexpected(
"'acceleration' command interface can only be used if 'velocity' and "
"'position' command interfaces are present");
}

if (
rsl::contains<std::vector<std::string>>(interface_types, "effort") &&
!(interface_types.size() == 1 ||
(interface_types.size() == 2 &&
rsl::contains<std::vector<std::string>>(interface_types, "position"))))
{
return tl::make_unexpected(
"'effort' command interface has to be used alone or with a 'position' interface");
}

return {};
}

/**
* \brief Validate command interface type combinations for joint trajectory controller.
*
* \param[in] parameter The rclcpp parameter containing the command interface types.
* \return tl::expected<void, std::string> An empty expected on success, or an error message on
* failure.
*/
tl::expected<void, std::string> command_interface_type_combinations(
rclcpp::Parameter const & parameter);

/**
* \brief Validate state interface type combinations for joint trajectory controller.
*
* \param[in] parameter The rclcpp parameter containing the state interface types.
* \return tl::expected<void, std::string> An empty expected on success, or an error message on
* failure.
*/
tl::expected<void, std::string> state_interface_type_combinations(
rclcpp::Parameter const & parameter)
{
auto const & interface_types = parameter.as_string_array();

// Valid combinations are
// 1. position [velocity, [acceleration]]

if (
rsl::contains<std::vector<std::string>>(interface_types, "velocity") &&
!rsl::contains<std::vector<std::string>>(interface_types, "position"))
{
return tl::make_unexpected(
"'velocity' state interface cannot be used if 'position' interface "
"is missing.");
}

if (
rsl::contains<std::vector<std::string>>(interface_types, "acceleration") &&
(!rsl::contains<std::vector<std::string>>(interface_types, "position") ||
!rsl::contains<std::vector<std::string>>(interface_types, "velocity")))
{
return tl::make_unexpected(
"'acceleration' state interface cannot be used if 'position' and 'velocity' "
"interfaces are not present.");
}

return {};
}
rclcpp::Parameter const & parameter);

} // namespace joint_trajectory_controller

Expand Down
94 changes: 94 additions & 0 deletions joint_trajectory_controller/src/validate_jtc_parameters.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,94 @@
// Copyright (c) 2022 ros2_control Development Team
//
// 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.

#include "joint_trajectory_controller/validate_jtc_parameters.hpp"

namespace joint_trajectory_controller
{

tl::expected<void, std::string> command_interface_type_combinations(
rclcpp::Parameter const & parameter)
{
auto const & interface_types = parameter.as_string_array();

// Check if command interfaces combination is valid. Valid combinations are:
// 1. effort
// 2. velocity
// 3. position [velocity, [acceleration]]
// 4. position, effort

if (
rsl::contains<std::vector<std::string>>(interface_types, "velocity") &&
interface_types.size() > 1 &&
!rsl::contains<std::vector<std::string>>(interface_types, "position"))
{
return tl::make_unexpected(
"'velocity' command interface can be used either alone or 'position' "
"command interface has to be present");
}

if (
rsl::contains<std::vector<std::string>>(interface_types, "acceleration") &&
(!rsl::contains<std::vector<std::string>>(interface_types, "velocity") &&
!rsl::contains<std::vector<std::string>>(interface_types, "position")))
{
return tl::make_unexpected(
"'acceleration' command interface can only be used if 'velocity' and "
"'position' command interfaces are present");
}

if (
rsl::contains<std::vector<std::string>>(interface_types, "effort") &&
!(interface_types.size() == 1 ||
(interface_types.size() == 2 &&
rsl::contains<std::vector<std::string>>(interface_types, "position"))))
{
return tl::make_unexpected(
"'effort' command interface has to be used alone or with a 'position' interface");
}

return {};
}

tl::expected<void, std::string> state_interface_type_combinations(
rclcpp::Parameter const & parameter)
{
auto const & interface_types = parameter.as_string_array();

// Valid combinations are
// 1. position [velocity, [acceleration]]

if (
rsl::contains<std::vector<std::string>>(interface_types, "velocity") &&
!rsl::contains<std::vector<std::string>>(interface_types, "position"))
{
return tl::make_unexpected(
"'velocity' state interface cannot be used if 'position' interface "
"is missing.");
}

if (
rsl::contains<std::vector<std::string>>(interface_types, "acceleration") &&
(!rsl::contains<std::vector<std::string>>(interface_types, "position") ||
!rsl::contains<std::vector<std::string>>(interface_types, "velocity")))
{
return tl::make_unexpected(
"'acceleration' state interface cannot be used if 'position' and 'velocity' "
"interfaces are not present.");
}

return {};
}

} // namespace joint_trajectory_controller
Loading