diff --git a/lbr_fri_ros2/include/lbr_fri_ros2/formatting.hpp b/lbr_fri_ros2/include/lbr_fri_ros2/formatting.hpp index e44d5dd3..debb2e86 100644 --- a/lbr_fri_ros2/include/lbr_fri_ros2/formatting.hpp +++ b/lbr_fri_ros2/include/lbr_fri_ros2/formatting.hpp @@ -61,7 +61,7 @@ struct EnumMaps { case KUKA::FRI::EClientCommandMode::POSITION: return "POSITION"; #endif -#if FRICLIENT_VERSION_MAJOR == 2 +#if FRICLIENT_VERSION_MAJOR >= 2 case KUKA::FRI::EClientCommandMode::JOINT_POSITION: return "JOINT_POSITION"; case KUKA::FRI::EClientCommandMode::CARTESIAN_POSE: diff --git a/lbr_fri_ros2/src/async_client.cpp b/lbr_fri_ros2/src/async_client.cpp index a32e7ae1..5c572fcc 100644 --- a/lbr_fri_ros2/src/async_client.cpp +++ b/lbr_fri_ros2/src/async_client.cpp @@ -21,7 +21,7 @@ AsyncClient::AsyncClient(const KUKA::FRI::EClientCommandMode &client_command_mod #if FRICLIENT_VERSION_MAJOR == 1 case KUKA::FRI::EClientCommandMode::POSITION: #endif -#if FRICLIENT_VERSION_MAJOR == 2 +#if FRICLIENT_VERSION_MAJOR >= 2 case KUKA::FRI::EClientCommandMode::JOINT_POSITION: #endif { diff --git a/lbr_fri_ros2/src/interfaces/position_command.cpp b/lbr_fri_ros2/src/interfaces/position_command.cpp index 786fd479..0a81bfe6 100644 --- a/lbr_fri_ros2/src/interfaces/position_command.cpp +++ b/lbr_fri_ros2/src/interfaces/position_command.cpp @@ -19,7 +19,7 @@ void PositionCommandInterface::buffered_command_to_fri(fri_command_t_ref command throw std::runtime_error(err); } #endif -#if FRICLIENT_VERSION_MAJOR == 2 +#if FRICLIENT_VERSION_MAJOR >= 2 if (state.client_command_mode != KUKA::FRI::EClientCommandMode::JOINT_POSITION) { std::string err = "Expected robot in " + diff --git a/lbr_fri_ros2/test/test_command_interfaces.cpp b/lbr_fri_ros2/test/test_command_interfaces.cpp index 9f956ca0..3ab403cb 100644 --- a/lbr_fri_ros2/test/test_command_interfaces.cpp +++ b/lbr_fri_ros2/test/test_command_interfaces.cpp @@ -36,7 +36,7 @@ class TestCommandInterfaces : public ::testing::Test { #if FRICLIENT_VERSION_MAJOR == 1 case KUKA::FRI::EClientCommandMode::POSITION: #endif -#if FRICLIENT_VERSION_MAJOR == 2 +#if FRICLIENT_VERSION_MAJOR >= 2 case KUKA::FRI::EClientCommandMode::JOINT_POSITION: #endif { @@ -146,7 +146,7 @@ TEST_F(TestCommandInterfaces, TestPositionCommandInterface) { #if FRICLIENT_VERSION_MAJOR == 1 set_up(KUKA::FRI::EClientCommandMode::POSITION); #endif -#if FRICLIENT_VERSION_MAJOR == 2 +#if FRICLIENT_VERSION_MAJOR >= 2 set_up(KUKA::FRI::EClientCommandMode::JOINT_POSITION); #endif test_simple(); diff --git a/lbr_fri_ros2_stack/package.xml b/lbr_fri_ros2_stack/package.xml index c3679e7b..fc3ff906 100644 --- a/lbr_fri_ros2_stack/package.xml +++ b/lbr_fri_ros2_stack/package.xml @@ -9,12 +9,12 @@ ament_cmake + lbr_fri_idl + lbr_fri_ros2 + lbr_ros2_control + lbr_bringup - lbr_demos lbr_description - lbr_fri_idl - lbr_fri_ros2 - lbr_ros2_control ament_cmake diff --git a/lbr_ros2_control/config/lbr_system_interface.xacro b/lbr_ros2_control/config/lbr_system_interface.xacro index cbb7d1db..8c78b289 100644 --- a/lbr_ros2_control/config/lbr_system_interface.xacro +++ b/lbr_ros2_control/config/lbr_system_interface.xacro @@ -103,7 +103,9 @@ - + + + diff --git a/lbr_ros2_control/config/lbr_system_parameters.yaml b/lbr_ros2_control/config/lbr_system_parameters.yaml index ff044a74..eee534db 100644 --- a/lbr_ros2_control/config/lbr_system_parameters.yaml +++ b/lbr_ros2_control/config/lbr_system_parameters.yaml @@ -1,4 +1,8 @@ # these parameters are read by the lbr_system_interface.xacro and configure the lbr_ros2_control::SystemInterface +fri_client_version: # FRI client version is used to determine required interfaces in lbr_system_interface.xacro + major: 1 + minor: 15 + hardware: client_command_mode: position # the command mode specifies the user-sent commands. Available: [position, torque, wrench] port_id: 30200 # port id for the UDP communication. Useful in multi-robot setups @@ -11,7 +15,7 @@ hardware: pid_i_min: 0.0 # min integral value for the joint position command pid_antiwindup: false # enable antiwindup for the joint position command command_guard_variant: default # if requested position / velocities beyond limits, CommandGuard will be triggered and shut the connection. Available: [default, safe_stop] - external_torque_cutoff_frequency: 10 # low-pass filter for the external joint torque measurements [Hz] + external_torque_cutoff_frequency: 10 # low-pass filter for the external joint torque measurements [Hz] measured_torque_cutoff_frequency: 10 # low-pass filter for the joint torque measurements [Hz] open_loop: true # KUKA works the best in open_loop control mode diff --git a/lbr_ros2_control/include/lbr_ros2_control/system_interface.hpp b/lbr_ros2_control/include/lbr_ros2_control/system_interface.hpp index f8756b19..9f4350cc 100644 --- a/lbr_ros2_control/include/lbr_ros2_control/system_interface.hpp +++ b/lbr_ros2_control/include/lbr_ros2_control/system_interface.hpp @@ -34,7 +34,7 @@ struct SystemInterfaceParameters { #if FRICLIENT_VERSION_MAJOR == 1 KUKA::FRI::EClientCommandMode client_command_mode{KUKA::FRI::EClientCommandMode::POSITION}; #endif -#if FRICLIENT_VERSION_MAJOR == 2 +#if FRICLIENT_VERSION_MAJOR >= 2 KUKA::FRI::EClientCommandMode client_command_mode{KUKA::FRI::EClientCommandMode::JOINT_POSITION}; #endif int32_t port_id{30200}; @@ -68,7 +68,12 @@ class SystemInterface : public hardware_interface::SystemInterface { protected: static constexpr char LOGGER_NAME[] = "lbr_ros2_control::SystemInterface"; +#if FRICLIENT_VERSION_MAJOR == 1 static constexpr uint8_t LBR_FRI_STATE_INTERFACE_SIZE = 7; +#endif +#if FRICLIENT_VERSION_MAJOR >= 2 + static constexpr uint8_t LBR_FRI_STATE_INTERFACE_SIZE = 6; +#endif static constexpr uint8_t LBR_FRI_COMMAND_INTERFACE_SIZE = 2; static constexpr uint8_t LBR_FRI_SENSORS = 2; static constexpr uint8_t AUXILIARY_SENSOR_SIZE = 12; diff --git a/lbr_ros2_control/src/system_interface.cpp b/lbr_ros2_control/src/system_interface.cpp index 4dae0dc0..6ed6d513 100644 --- a/lbr_ros2_control/src/system_interface.cpp +++ b/lbr_ros2_control/src/system_interface.cpp @@ -325,7 +325,7 @@ bool SystemInterface::parse_parameters_(const hardware_interface::HardwareInfo & #if FRICLIENT_VERSION_MAJOR == 1 parameters_.client_command_mode = KUKA::FRI::EClientCommandMode::POSITION; #endif -#if FRICLIENT_VERSION_MAJOR == 2 +#if FRICLIENT_VERSION_MAJOR >= 2 parameters_.client_command_mode = KUKA::FRI::EClientCommandMode::JOINT_POSITION; #endif } else if (client_command_mode == "torque") {