Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
franka_hw::FrankaCombinedHW Class Reference

#include <franka_combined_hw.h>

Inheritance diagram for franka_hw::FrankaCombinedHW:
Inheritance graph
[legend]

Public Member Functions

void connect ()
 Calls connect on all hardware classes that are of type FrankaCombinableHW. More...
 
bool controllerNeedsReset ()
 Checks whether the controller needs to be reset. More...
 
bool disconnect ()
 Tries to disconnect on all hardware classes that are of type FrankaCombinableHW. More...
 
 FrankaCombinedHW ()
 Creates an instance of CombinedFrankaHW. More...
 
bool hasError ()
 Checks whether the robots are in error or reflex mode. More...
 
bool init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
 The init function is called to initialize the CombinedFrankaHW from a non-realtime thread. More...
 
void read (const ros::Time &time, const ros::Duration &period) override
 Reads data from the robot HW. More...
 
 ~FrankaCombinedHW () override=default
 
- Public Member Functions inherited from combined_robot_hw::CombinedRobotHW
void doSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) override
 
bool prepareSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) override
 
void write (const ros::Time &time, const ros::Duration &period) override
 
- 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::unique_ptr< actionlib::SimpleActionServer< franka_msgs::ErrorRecoveryAction > > combined_recovery_action_server_
 
ros::ServiceServer connect_server_
 
ros::ServiceServer disconnect_server_
 
- Protected Attributes inherited from combined_robot_hw::CombinedRobotHW
std::vector< hardware_interface::RobotHWSharedPtrrobot_hw_list_
 
pluginlib::ClassLoader< hardware_interface::RobotHWrobot_hw_loader_
 
ros::NodeHandle robot_hw_nh_
 
ros::NodeHandle root_nh_
 
- 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 Member Functions

void handleError ()
 
void triggerError ()
 

Private Attributes

bool is_recovering_ {false}
 

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
 
- Protected Member Functions inherited from combined_robot_hw::CombinedRobotHW
void filterControllerList (const std::list< hardware_interface::ControllerInfo > &list, std::list< hardware_interface::ControllerInfo > &filtered_list, hardware_interface::RobotHWSharedPtr robot_hw)
 
virtual bool loadRobotHW (const std::string &name)
 

Detailed Description

Definition at line 17 of file franka_combined_hw.h.

Constructor & Destructor Documentation

◆ FrankaCombinedHW()

franka_hw::FrankaCombinedHW::FrankaCombinedHW ( )
default

Creates an instance of CombinedFrankaHW.

◆ ~FrankaCombinedHW()

franka_hw::FrankaCombinedHW::~FrankaCombinedHW ( )
overridedefault

Member Function Documentation

◆ connect()

void franka_hw::FrankaCombinedHW::connect ( )

Calls connect on all hardware classes that are of type FrankaCombinableHW.

Definition at line 150 of file franka_combined_hw.cpp.

◆ controllerNeedsReset()

bool franka_hw::FrankaCombinedHW::controllerNeedsReset ( )

Checks whether the controller needs to be reset.

Returns
True if the controllers needs to be reset, false otherwise.

Definition at line 102 of file franka_combined_hw.cpp.

◆ disconnect()

bool franka_hw::FrankaCombinedHW::disconnect ( )

Tries to disconnect on all hardware classes that are of type FrankaCombinableHW.

Returns
true if successful, false otherwise.

Definition at line 159 of file franka_combined_hw.cpp.

◆ handleError()

void franka_hw::FrankaCombinedHW::handleError ( )
private

Definition at line 117 of file franka_combined_hw.cpp.

◆ hasError()

bool franka_hw::FrankaCombinedHW::hasError ( )

Checks whether the robots are in error or reflex mode.

Returns
true if in error state, false otherwise.

Definition at line 124 of file franka_combined_hw.cpp.

◆ init()

bool franka_hw::FrankaCombinedHW::init ( ros::NodeHandle root_nh,
ros::NodeHandle robot_hw_nh 
)
overridevirtual

The init function is called to initialize the CombinedFrankaHW from a non-realtime thread.

Parameters
[in]root_nhA NodeHandle in the root of the caller namespace.
[in]robot_hw_nhA NodeHandle in the namespace from which the RobotHW. should read its configuration.
Returns
True if initialization was successful.

Reimplemented from combined_robot_hw::CombinedRobotHW.

Definition at line 21 of file franka_combined_hw.cpp.

◆ read()

void franka_hw::FrankaCombinedHW::read ( const ros::Time time,
const ros::Duration period 
)
overridevirtual

Reads data from the robot HW.

Parameters
[in]timeThe current time.
[in]periodThe time passed since the last call to read.

Reimplemented from combined_robot_hw::CombinedRobotHW.

Definition at line 96 of file franka_combined_hw.cpp.

◆ triggerError()

void franka_hw::FrankaCombinedHW::triggerError ( )
private

Definition at line 138 of file franka_combined_hw.cpp.

Member Data Documentation

◆ combined_recovery_action_server_

std::unique_ptr<actionlib::SimpleActionServer<franka_msgs::ErrorRecoveryAction> > franka_hw::FrankaCombinedHW::combined_recovery_action_server_
protected

Definition at line 71 of file franka_combined_hw.h.

◆ connect_server_

ros::ServiceServer franka_hw::FrankaCombinedHW::connect_server_
protected

Definition at line 72 of file franka_combined_hw.h.

◆ disconnect_server_

ros::ServiceServer franka_hw::FrankaCombinedHW::disconnect_server_
protected

Definition at line 73 of file franka_combined_hw.h.

◆ is_recovering_

bool franka_hw::FrankaCombinedHW::is_recovering_ {false}
private

Definition at line 78 of file franka_combined_hw.h.


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


franka_hw
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:21