8#include <hardware_interface/internal/hardware_resource_manager.h>
18 : name_(std::move(name)), distance_(distance), strength_(strength)
21 throw hardware_interface::HardwareInterfaceException(
"Cannot create handle '" + name +
22 "'. distance_ pointer is null.");
24 throw hardware_interface::HardwareInterfaceException(
"Cannot create handle '" + name +
25 "'. strength_ pointer is null.");
52 :
public hardware_interface::HardwareResourceManager<TofRadarHandle, hardware_interface::DontClaimResources>
Definition tof_radar_interface.h:13
double getStrength() const
Definition tof_radar_interface.h:39
TofRadarHandle(std::string name, double *distance, double *strength)
Definition tof_radar_interface.h:17
double getDistance() const
Definition tof_radar_interface.h:33
std::string getName() const
Definition tof_radar_interface.h:28
Definition tof_radar_interface.h:53
Definition actuator_extra_interface.h:44