Skip to content

Commit

Permalink
Introuduce gen param library.
Browse files Browse the repository at this point in the history
  • Loading branch information
livanov93 committed Feb 23, 2023
1 parent bb54c12 commit 55f6364
Show file tree
Hide file tree
Showing 6 changed files with 227 additions and 74 deletions.
26 changes: 24 additions & 2 deletions ign_ros2_control/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,12 @@ find_package(hardware_interface REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(yaml_cpp_vendor REQUIRED)
find_package(generate_parameter_library REQUIRED)

generate_parameter_library(ign_ros2_control_parameters
src/ign_ros2_control_parameters.yaml
include/ign_ros2_control/validate_system_parameters.hpp
)

if("$ENV{IGNITION_VERSION}" STREQUAL "citadel")
find_package(ignition-gazebo3 REQUIRED)
Expand Down Expand Up @@ -82,9 +88,13 @@ target_link_libraries(ign_hardware_plugins
ignition-gazebo${IGN_GAZEBO_VER}::core
)

target_link_libraries(ign_hardware_plugins
ign_ros2_control_parameters
)

## Install
install(TARGETS
ign_hardware_plugins
install(TARGETS ign_hardware_plugins ign_ros2_control_parameters
EXPORT export_ign_ros2_control
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
Expand All @@ -99,12 +109,24 @@ endif()
ament_export_include_directories(include)
ament_export_libraries(${PROJECT_NAME} ign_hardware_plugins)

ament_export_targets(
export_ign_ros2_control HAS_LIBRARY_TARGET
)
# Install directories
install(TARGETS ${PROJECT_NAME}-system
DESTINATION lib
)

pluginlib_export_plugin_description_file(ign_ros2_control ign_hardware_plugins.xml)

ament_export_dependencies(
ament_index_cpp
controller_manager
hardware_interface
pluginlib
rclcpp
yaml_cpp_vendor
rclcpp_lifecycle
)
# Setup the project
ament_package()
10 changes: 10 additions & 0 deletions ign_ros2_control/include/ign_ros2_control/ign_system.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@
#include "rclcpp_lifecycle/state.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"

#include "ign_ros2_control_parameters.hpp"

namespace ign_ros2_control
{
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
Expand Down Expand Up @@ -88,6 +90,14 @@ class IgnitionSystem : public IgnitionSystemInterface

/// \brief Private data class
std::unique_ptr<IgnitionSystemPrivate> dataPtr;

rcl_interfaces::msg::SetParametersResult myCallback(const std::vector<rclcpp::Parameter> & parameters);
rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr cb_;

rclcpp::Node::SharedPtr node_;

std::thread spin_thread_;

};

} // namespace ign_ros2_control
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
#ifndef IGN_ROS2_CONTROL__VALIDATE_SYSTEM_PARAMETERS_HPP_
#define IGN_ROS2_CONTROL__VALIDATE_SYSTEM_PARAMETERS_HPP_

#include <string>

#include "parameter_traits/parameter_traits.hpp"

namespace parameter_traits
{

} // namespace parameter_traits

#endif // IGN_ROS2_CONTROL__VALIDATE_SYSTEM_PARAMETERS_HPP_
1 change: 1 addition & 0 deletions ign_ros2_control/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
<depend>rclcpp_lifecycle</depend>
<depend>hardware_interface</depend>
<depend>controller_manager</depend>
<depend>generate_parameter_library</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
51 changes: 51 additions & 0 deletions ign_ros2_control/src/ign_ros2_control_parameters.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
ignition_system_interface:
joints: {
type: string_array,
default_value: [],
description: "Names of joints used by the controller",
validation: {
unique<>: null,
}
}
gains:
__map_joints:
p: {
type: double,
default_value: 0.0,
description: "Proportional gain for PID"
}
i: {
type: double,
default_value: 0.0,
description: "Integral gain for PID"
}
d: {
type: double,
default_value: 0.0,
description: "Derivative gain for PID"
}
iMax: {
type: double,
default_value: 0.0,
description: "Integral positive clamp."
}
iMin: {
type: double,
default_value: 0.0,
description: "Integral negative clamp."
}
cmdMax: {
type: double,
default_value: 0.0,
description: "Maximum value for the PID command."
}
cmdMin: {
type: double,
default_value: 0.0,
description: "Maximum value for the PID command."
}
cmdOffset: {
type: double,
default_value: 0.0,
description: "Offset value for the command which is added to the result of the PID controller."
}
Loading

0 comments on commit 55f6364

Please sign in to comment.