Skip to content

Commit

Permalink
Preparation of Handles for Variant Support (ros-controls#1678)
Browse files Browse the repository at this point in the history
  • Loading branch information
mamueluth authored Aug 15, 2024
1 parent af4b48f commit eb4316b
Show file tree
Hide file tree
Showing 2 changed files with 45 additions and 43 deletions.
80 changes: 41 additions & 39 deletions hardware_interface/include/hardware_interface/handle.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,41 +16,45 @@
#define HARDWARE_INTERFACE__HANDLE_HPP_

#include <string>
#include <variant>

#include "hardware_interface/macros.hpp"

namespace hardware_interface
{

using HANDLE_DATATYPE = std::variant<double>;

/// A handle used to get and set a value on a given interface.
class ReadOnlyHandle
class Handle
{
public:
ReadOnlyHandle(
Handle(
const std::string & prefix_name, const std::string & interface_name,
double * value_ptr = nullptr)
: prefix_name_(prefix_name), interface_name_(interface_name), value_ptr_(value_ptr)
{
}

explicit ReadOnlyHandle(const std::string & interface_name)
explicit Handle(const std::string & interface_name)
: interface_name_(interface_name), value_ptr_(nullptr)
{
}

explicit ReadOnlyHandle(const char * interface_name)
explicit Handle(const char * interface_name)
: interface_name_(interface_name), value_ptr_(nullptr)
{
}

ReadOnlyHandle(const ReadOnlyHandle & other) = default;
Handle(const Handle & other) = default;

ReadOnlyHandle(ReadOnlyHandle && other) = default;
Handle(Handle && other) = default;

ReadOnlyHandle & operator=(const ReadOnlyHandle & other) = default;
Handle & operator=(const Handle & other) = default;

ReadOnlyHandle & operator=(ReadOnlyHandle && other) = default;
Handle & operator=(Handle && other) = default;

virtual ~ReadOnlyHandle() = default;
virtual ~Handle() = default;

/// Returns true if handle references a value.
inline operator bool() const { return value_ptr_ != nullptr; }
Expand All @@ -70,60 +74,58 @@ class ReadOnlyHandle

double get_value() const
{
// BEGIN (Handle export change): for backward compatibility
// TODO(Manuel) return value_ if old functionality is removed
THROW_ON_NULLPTR(value_ptr_);
return *value_ptr_;
// END
}

void set_value(double value)
{
// BEGIN (Handle export change): for backward compatibility
// TODO(Manuel) set value_ directly if old functionality is removed
THROW_ON_NULLPTR(this->value_ptr_);
*this->value_ptr_ = value;
// END
}

protected:
std::string prefix_name_;
std::string interface_name_;
HANDLE_DATATYPE value_;
// BEGIN (Handle export change): for backward compatibility
// TODO(Manuel) redeclare as HANDLE_DATATYPE * value_ptr_ if old functionality is removed
double * value_ptr_;
// END
};

class ReadWriteHandle : public ReadOnlyHandle
class StateInterface : public Handle
{
public:
ReadWriteHandle(
explicit StateInterface(
const std::string & prefix_name, const std::string & interface_name,
double * value_ptr = nullptr)
: ReadOnlyHandle(prefix_name, interface_name, value_ptr)
{
}

explicit ReadWriteHandle(const std::string & interface_name) : ReadOnlyHandle(interface_name) {}

explicit ReadWriteHandle(const char * interface_name) : ReadOnlyHandle(interface_name) {}

ReadWriteHandle(const ReadWriteHandle & other) = default;

ReadWriteHandle(ReadWriteHandle && other) = default;

ReadWriteHandle & operator=(const ReadWriteHandle & other) = default;

ReadWriteHandle & operator=(ReadWriteHandle && other) = default;

virtual ~ReadWriteHandle() = default;

void set_value(double value)
: Handle(prefix_name, interface_name, value_ptr)
{
THROW_ON_NULLPTR(this->value_ptr_);
*this->value_ptr_ = value;
}
};

class StateInterface : public ReadOnlyHandle
{
public:
StateInterface(const StateInterface & other) = default;

StateInterface(StateInterface && other) = default;

using ReadOnlyHandle::ReadOnlyHandle;
using Handle::Handle;
};

class CommandInterface : public ReadWriteHandle
class CommandInterface : public Handle
{
public:
explicit CommandInterface(
const std::string & prefix_name, const std::string & interface_name,
double * value_ptr = nullptr)
: Handle(prefix_name, interface_name, value_ptr)
{
}
/// CommandInterface copy constructor is actively deleted.
/**
* Command interfaces are having a unique ownership and thus
Expand All @@ -134,7 +136,7 @@ class CommandInterface : public ReadWriteHandle

CommandInterface(CommandInterface && other) = default;

using ReadWriteHandle::ReadWriteHandle;
using Handle::Handle;
};

} // namespace hardware_interface
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,17 +20,17 @@
namespace transmission_interface
{
/** A handle used to get and set a value on a given actuator interface. */
class ActuatorHandle : public hardware_interface::ReadWriteHandle
class ActuatorHandle : public hardware_interface::Handle
{
public:
using hardware_interface::ReadWriteHandle::ReadWriteHandle;
using hardware_interface::Handle::Handle;
};

/** A handle used to get and set a value on a given joint interface. */
class JointHandle : public hardware_interface::ReadWriteHandle
class JointHandle : public hardware_interface::Handle
{
public:
using hardware_interface::ReadWriteHandle::ReadWriteHandle;
using hardware_interface::Handle::Handle;
};

} // namespace transmission_interface
Expand Down

0 comments on commit eb4316b

Please sign in to comment.