Public Member Functions | Protected Attributes | Private Attributes | List of all members
SVHRosControlHWInterface Class Reference

This class defines a ros-control hardware interface. More...

#include <SVHRosControlHWInterface.h>

Inheritance diagram for SVHRosControlHWInterface:
Inheritance graph
[legend]

Public Member Functions

void doSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
 
virtual bool init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
 Initialize the hardware interface. More...
 
bool isEnabled () const
 
bool isFault ()
 Returns true, when at least one node in the hardware is in a fault state. More...
 
bool prepareSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
 
virtual void read (const ros::Time &time, const ros::Duration &period)
 Read the state from the robot hardware. More...
 
 SVHRosControlHWInterface ()
 
virtual void write (const ros::Time &time, const ros::Duration &period)
 write the command to the robot hardware. More...
 
 ~SVHRosControlHWInterface ()
 
- Public Member Functions inherited from hardware_interface::RobotHW
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual SwitchState switchResult () const
 
virtual SwitchState switchResult (const ControllerInfo &) const
 
virtual ~RobotHW ()=default
 
- Public Member Functions inherited from hardware_interface::InterfaceManager
T * get ()
 
std::vector< std::string > getInterfaceResources (std::string iface_type) const
 
std::vector< std::string > getNames () const
 
void registerInterface (T *iface)
 
void registerInterfaceManager (InterfaceManager *iface_man)
 

Protected Attributes

std::vector< std::string > m_channel_names
 
bool m_is_fault
 
std::vector< double > m_joint_effort
 
joint_limits_interface::JointLimits m_joint_limits
 
std::vector< double > m_joint_position_commands
 
std::vector< double > m_joint_positions
 
joint_limits_interface::SoftJointLimits m_joint_soft_limits
 
hardware_interface::JointStateInterface m_joint_state_interface
 
std::vector< double > m_joint_velocity
 
ros::NodeHandle m_node_handle
 Creates a joint_state message from the current joint angles and returns it. More...
 
std::vector< uint8_t > m_node_ids
 
size_t m_num_joints
 
hardware_interface::PositionJointInterface m_position_joint_interface
 
std::shared_ptr< SVHWrapperm_svh
 Handle to the SVH finger manager for library access. More...
 
- Protected Attributes inherited from hardware_interface::InterfaceManager
std::vector< ResourceManagerBase * > interface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

Private Attributes

bool m_hardware_ready
 

Additional Inherited Members

- Public Types inherited from hardware_interface::RobotHW
enum  SwitchState { SwitchState::DONE, SwitchState::ONGOING, SwitchState::ERROR }
 
- Protected Types inherited from hardware_interface::InterfaceManager
typedef std::vector< InterfaceManager * > InterfaceManagerVector
 
typedef std::map< std::string, void * > InterfaceMap
 
typedef std::map< std::string, std::vector< std::string > > ResourceMap
 
typedef std::map< std::string, size_t > SizeMap
 

Detailed Description

This class defines a ros-control hardware interface.

Definition at line 51 of file SVHRosControlHWInterface.h.

Constructor & Destructor Documentation

◆ SVHRosControlHWInterface()

SVHRosControlHWInterface::SVHRosControlHWInterface ( )

Definition at line 49 of file SVHRosControlHWInterface.cpp.

◆ ~SVHRosControlHWInterface()

SVHRosControlHWInterface::~SVHRosControlHWInterface ( )

Definition at line 51 of file SVHRosControlHWInterface.cpp.

Member Function Documentation

◆ doSwitch()

void SVHRosControlHWInterface::doSwitch ( const std::list< hardware_interface::ControllerInfo > &  start_list,
const std::list< hardware_interface::ControllerInfo > &  stop_list 
)
virtual

Reimplemented from hardware_interface::RobotHW.

Definition at line 184 of file SVHRosControlHWInterface.cpp.

◆ init()

bool SVHRosControlHWInterface::init ( ros::NodeHandle root_nh,
ros::NodeHandle robot_hw_nh 
)
virtual

Initialize the hardware interface.

Reimplemented from hardware_interface::RobotHW.

Definition at line 54 of file SVHRosControlHWInterface.cpp.

◆ isEnabled()

bool SVHRosControlHWInterface::isEnabled ( ) const

Definition at line 191 of file SVHRosControlHWInterface.cpp.

◆ isFault()

bool SVHRosControlHWInterface::isFault ( )
inline

Returns true, when at least one node in the hardware is in a fault state.

Definition at line 77 of file SVHRosControlHWInterface.h.

◆ prepareSwitch()

bool SVHRosControlHWInterface::prepareSwitch ( const std::list< hardware_interface::ControllerInfo > &  start_list,
const std::list< hardware_interface::ControllerInfo > &  stop_list 
)
virtual

Reimplemented from hardware_interface::RobotHW.

Definition at line 177 of file SVHRosControlHWInterface.cpp.

◆ read()

void SVHRosControlHWInterface::read ( const ros::Time time,
const ros::Duration period 
)
virtual

Read the state from the robot hardware.

Reimplemented from hardware_interface::RobotHW.

Definition at line 104 of file SVHRosControlHWInterface.cpp.

◆ write()

void SVHRosControlHWInterface::write ( const ros::Time time,
const ros::Duration period 
)
virtual

write the command to the robot hardware.

Reimplemented from hardware_interface::RobotHW.

Definition at line 146 of file SVHRosControlHWInterface.cpp.

Member Data Documentation

◆ m_channel_names

std::vector<std::string> SVHRosControlHWInterface::m_channel_names
protected

Definition at line 95 of file SVHRosControlHWInterface.h.

◆ m_hardware_ready

bool SVHRosControlHWInterface::m_hardware_ready
private

Definition at line 108 of file SVHRosControlHWInterface.h.

◆ m_is_fault

bool SVHRosControlHWInterface::m_is_fault
protected

Definition at line 101 of file SVHRosControlHWInterface.h.

◆ m_joint_effort

std::vector<double> SVHRosControlHWInterface::m_joint_effort
protected

Definition at line 98 of file SVHRosControlHWInterface.h.

◆ m_joint_limits

joint_limits_interface::JointLimits SVHRosControlHWInterface::m_joint_limits
protected

Definition at line 103 of file SVHRosControlHWInterface.h.

◆ m_joint_position_commands

std::vector<double> SVHRosControlHWInterface::m_joint_position_commands
protected

Definition at line 99 of file SVHRosControlHWInterface.h.

◆ m_joint_positions

std::vector<double> SVHRosControlHWInterface::m_joint_positions
protected

Definition at line 96 of file SVHRosControlHWInterface.h.

◆ m_joint_soft_limits

joint_limits_interface::SoftJointLimits SVHRosControlHWInterface::m_joint_soft_limits
protected

Definition at line 105 of file SVHRosControlHWInterface.h.

◆ m_joint_state_interface

hardware_interface::JointStateInterface SVHRosControlHWInterface::m_joint_state_interface
protected

Definition at line 89 of file SVHRosControlHWInterface.h.

◆ m_joint_velocity

std::vector<double> SVHRosControlHWInterface::m_joint_velocity
protected

Definition at line 97 of file SVHRosControlHWInterface.h.

◆ m_node_handle

ros::NodeHandle SVHRosControlHWInterface::m_node_handle
protected

Creates a joint_state message from the current joint angles and returns it.

Definition at line 84 of file SVHRosControlHWInterface.h.

◆ m_node_ids

std::vector<uint8_t> SVHRosControlHWInterface::m_node_ids
protected

Definition at line 94 of file SVHRosControlHWInterface.h.

◆ m_num_joints

size_t SVHRosControlHWInterface::m_num_joints
protected

Definition at line 92 of file SVHRosControlHWInterface.h.

◆ m_position_joint_interface

hardware_interface::PositionJointInterface SVHRosControlHWInterface::m_position_joint_interface
protected

Definition at line 90 of file SVHRosControlHWInterface.h.

◆ m_svh

std::shared_ptr<SVHWrapper> SVHRosControlHWInterface::m_svh
protected

Handle to the SVH finger manager for library access.

Definition at line 86 of file SVHRosControlHWInterface.h.


The documentation for this class was generated from the following files:


schunk_svh_driver
Author(s): Georg Heppner , Felix Exner , Pascal Becker , Johannes Mangler
autogenerated on Sat Apr 15 2023 02:24:55