Skip to content

Commit

Permalink
replaced types among interfaces
Browse files Browse the repository at this point in the history
  • Loading branch information
mhubii committed Oct 22, 2024
1 parent 079232b commit ea11f1e
Show file tree
Hide file tree
Showing 4 changed files with 20 additions and 33 deletions.
12 changes: 1 addition & 11 deletions lbr_fri_ros2/include/lbr_fri_ros2/interfaces/base_command.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,28 +10,18 @@
#include "rclcpp/logging.hpp"

#include "friClientVersion.h"
#include "friLBRClient.h"

#include "lbr_fri_idl/msg/lbr_command.hpp"
#include "lbr_fri_ros2/command_guard.hpp"
#include "lbr_fri_ros2/filters.hpp"
#include "lbr_fri_ros2/formatting.hpp"
#include "lbr_fri_ros2/types.hpp"

namespace lbr_fri_ros2 {
class BaseCommandInterface {
protected:
virtual std::string LOGGER_NAME() const = 0;

// ROS IDL types
using idl_command_t = lbr_fri_idl::msg::LBRCommand;
using const_idl_command_t_ref = const idl_command_t &;
using idl_state_t = lbr_fri_idl::msg::LBRState;
using const_idl_state_t_ref = const idl_state_t &;

// FRI types
using fri_command_t = KUKA::FRI::LBRCommand;
using fri_command_t_ref = fri_command_t &;

public:
BaseCommandInterface() = delete;
BaseCommandInterface(const PIDParameters &pid_parameters,
Expand Down
15 changes: 2 additions & 13 deletions lbr_fri_ros2/include/lbr_fri_ros2/interfaces/state.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,10 @@
#include "rclcpp/logging.hpp"

#include "friClientVersion.h"
#include "friLBRClient.h"

#include "lbr_fri_idl/msg/lbr_state.hpp"
#include "lbr_fri_ros2/filters.hpp"
#include "lbr_fri_ros2/types.hpp"

namespace lbr_fri_ros2 {
struct StateInterfaceParameters {
Expand All @@ -22,25 +22,14 @@ class StateInterface {
protected:
static constexpr char LOGGER_NAME[] = "lbr_fri_ros2::StateInterface";

// ROS IDL types
using idl_state_t = lbr_fri_idl::msg::LBRState;
using const_idl_state_t_ref = const idl_state_t &;
using idl_joint_pos_t = idl_state_t::_measured_joint_position_type;
using const_idl_joint_pos_t_ref = const idl_joint_pos_t &;

// FRI types
using fri_state_t = KUKA::FRI::LBRState;
using const_fri_state_t_ref = const fri_state_t &;
using fri_session_state_t = KUKA::FRI::ESessionState;

public:
StateInterface() = delete;
StateInterface(const StateInterfaceParameters &state_interface_parameters = {10.0, 10.0});

inline const_idl_state_t_ref get_state() const { return state_; };

void set_state(const_fri_state_t_ref state);
void set_state_open_loop(const_fri_state_t_ref state, const_idl_joint_pos_t_ref joint_position);
void set_state_open_loop(const_fri_state_t_ref state, const_jnt_array_t_ref joint_position);

inline void uninitialize() { state_initialized_ = false; }
inline bool is_initialized() const { return state_initialized_; };
Expand Down
16 changes: 12 additions & 4 deletions lbr_fri_ros2/include/lbr_fri_ros2/types.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
#include <cstdint>
#include <string>

#include "friLBRState.h"
#include "friLBRClient.h"

#include "lbr_fri_idl/msg/lbr_command.hpp"
#include "lbr_fri_idl/msg/lbr_state.hpp"
Expand All @@ -21,15 +21,23 @@ using jnt_name_array_t = std::array<std::string, KUKA::FRI::LBRState::NUMBER_OF_
using jnt_name_array_t_ref = jnt_name_array_t &;
using const_jnt_name_array_t_ref = const jnt_name_array_t &;

// cartesian dof
// Cartesian dof
constexpr std::uint8_t CARTESIAN_DOF = 6;

// cartesian positions, velocities, accelerations, torques etc.
// Cartesian positions, velocities, accelerations, torques etc.
using cart_array_t = std::array<double, CARTESIAN_DOF>;
using cart_array_t_ref = cart_array_t &;
using const_cart_array_t_ref = const cart_array_t &;

// idl types
// FRI types
using fri_command_t = KUKA::FRI::LBRCommand;
using fri_command_t_ref = fri_command_t &;
using const_fri_command_t_ref = const fri_command_t &;
using fri_state_t = KUKA::FRI::LBRState;
using fri_state_t_ref = fri_state_t &;
using const_fri_state_t_ref = const fri_state_t &;

// ROS IDL types
using idl_command_t = lbr_fri_idl::msg::LBRCommand;
using idl_command_t_ref = idl_command_t &;
using const_idl_command_t_ref = const idl_command_t &;
Expand Down
10 changes: 5 additions & 5 deletions lbr_fri_ros2/src/interfaces/state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@ void StateInterface::set_state(const_fri_state_t_ref state) {
state_.control_mode = state.getControlMode();
state_.drive_state = state.getDriveState();
external_torque_filter_.compute(state.getExternalTorque(), state_.external_torque);
if (state.getSessionState() == fri_session_state_t::COMMANDING_WAIT ||
state.getSessionState() == fri_session_state_t::COMMANDING_ACTIVE) {
if (state.getSessionState() == KUKA::FRI::ESessionState::COMMANDING_WAIT ||
state.getSessionState() == KUKA::FRI::ESessionState::COMMANDING_ACTIVE) {
std::memcpy(state_.ipo_joint_position.data(), state.getIpoJointPosition(),
sizeof(double) * fri_state_t::NUMBER_OF_JOINTS);
}
Expand All @@ -41,7 +41,7 @@ void StateInterface::set_state(const_fri_state_t_ref state) {
};

void StateInterface::set_state_open_loop(const_fri_state_t_ref state,
const_idl_joint_pos_t_ref joint_position) {
const_jnt_array_t_ref joint_position) {
state_.client_command_mode = state.getClientCommandMode();
#if FRI_CLIENT_VERSION_MAJOR == 1
std::memcpy(state_.commanded_joint_position.data(), state.getCommandedJointPosition(),
Expand All @@ -53,8 +53,8 @@ void StateInterface::set_state_open_loop(const_fri_state_t_ref state,
state_.control_mode = state.getControlMode();
state_.drive_state = state.getDriveState();
external_torque_filter_.compute(state.getExternalTorque(), state_.external_torque);
if (state.getSessionState() == fri_session_state_t::COMMANDING_WAIT ||
state.getSessionState() == fri_session_state_t::COMMANDING_ACTIVE) {
if (state.getSessionState() == KUKA::FRI::ESessionState::COMMANDING_WAIT ||
state.getSessionState() == KUKA::FRI::ESessionState::COMMANDING_ACTIVE) {
std::memcpy(state_.ipo_joint_position.data(), state.getIpoJointPosition(),
sizeof(double) * fri_state_t::NUMBER_OF_JOINTS);
}
Expand Down

0 comments on commit ea11f1e

Please sign in to comment.