Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

State Interface Fix FRI >= 2 #183

Closed
wants to merge 6 commits into from
Closed
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
2 changes: 1 addition & 1 deletion lbr_fri_ros2/include/lbr_fri_ros2/formatting.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
2 changes: 1 addition & 1 deletion lbr_fri_ros2/src/async_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down
2 changes: 1 addition & 1 deletion lbr_fri_ros2/src/interfaces/position_command.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 " +
Expand Down
4 changes: 2 additions & 2 deletions lbr_fri_ros2/test/test_command_interfaces.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down Expand Up @@ -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();
Expand Down
8 changes: 4 additions & 4 deletions lbr_fri_ros2_stack/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,12 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>lbr_fri_idl</depend>
<depend>lbr_fri_ros2</depend>
<depend>lbr_ros2_control</depend>

<exec_depend>lbr_bringup</exec_depend>
<exec_depend>lbr_demos</exec_depend>
<exec_depend>lbr_description</exec_depend>
<exec_depend>lbr_fri_idl</exec_depend>
<exec_depend>lbr_fri_ros2</exec_depend>
<exec_depend>lbr_ros2_control</exec_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
4 changes: 3 additions & 1 deletion lbr_ros2_control/config/lbr_system_interface.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,9 @@
<state_interface name="velocity" />
<state_interface name="effort" />
<xacro:unless value="${sim}">
<state_interface name="commanded_joint_position" />
mhubii marked this conversation as resolved.
Show resolved Hide resolved
<xacro:if value="${system_parameters['fri_client_version']['major'] == 1}">
<state_interface name="commanded_joint_position" />
</xacro:if>
<state_interface name="commanded_torque" />
<state_interface name="external_torque" />
<state_interface name="ipo_joint_position" />
Expand Down
6 changes: 5 additions & 1 deletion lbr_ros2_control/config/lbr_system_parameters.yaml
Original file line number Diff line number Diff line change
@@ -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
Copy link
Member Author

@mhubii mhubii May 30, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

is the user required to configure this, or can this be done automatically?

At least there should be a runtime error hinting to a potential mismatch.

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
Expand All @@ -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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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};
Expand Down Expand Up @@ -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;
mhubii marked this conversation as resolved.
Show resolved Hide resolved
#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;
Expand Down
2 changes: 1 addition & 1 deletion lbr_ros2_control/src/system_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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") {
Expand Down
Loading