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

bool controllerNeedsReset ()
 Checks whether the controller needs to be reset. More...
 
 FrankaCombinedHW ()
 Creates an instance of CombinedFrankaHW. 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
 CombinedRobotHW ()
 
virtual void doSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
 
virtual bool prepareSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
 
virtual void write (const ros::Time &time, const ros::Duration &period)
 
virtual ~CombinedRobotHW ()
 
- 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
 
 RobotHW ()
 
virtual ~RobotHW ()
 
- 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_
 
- 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
boost::ptr_vector< ResourceManagerBaseinterface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

Private Member Functions

void handleError ()
 
bool hasError ()
 
void triggerError ()
 

Private Attributes

bool is_recovering_ {false}
 

Additional Inherited Members

- 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

franka_hw::FrankaCombinedHW::FrankaCombinedHW ( )
default

Creates an instance of CombinedFrankaHW.

franka_hw::FrankaCombinedHW::~FrankaCombinedHW ( )
overridedefault

Member Function Documentation

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 63 of file franka_combined_hw.cpp.

void franka_hw::FrankaCombinedHW::handleError ( )
private

Definition at line 78 of file franka_combined_hw.cpp.

bool franka_hw::FrankaCombinedHW::hasError ( )
private

Definition at line 85 of file franka_combined_hw.cpp.

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 20 of file franka_combined_hw.cpp.

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 57 of file franka_combined_hw.cpp.

void franka_hw::FrankaCombinedHW::triggerError ( )
private

Definition at line 99 of file franka_combined_hw.cpp.

Member Data Documentation

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

Definition at line 55 of file franka_combined_hw.h.

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

Definition at line 61 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 Fri Oct 23 2020 03:47:05