#include <franka_combined_hw.h>

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::RobotHWSharedPtr > | robot_hw_list_ |
| pluginlib::ClassLoader< hardware_interface::RobotHW > | robot_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) |
Definition at line 17 of file franka_combined_hw.h.
|
default |
Creates an instance of CombinedFrankaHW.
|
overridedefault |
| 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.
| bool franka_hw::FrankaCombinedHW::controllerNeedsReset | ( | ) |
Checks whether the controller needs to be reset.
Definition at line 102 of file franka_combined_hw.cpp.
| bool franka_hw::FrankaCombinedHW::disconnect | ( | ) |
Tries to disconnect on all hardware classes that are of type FrankaCombinableHW.
Definition at line 159 of file franka_combined_hw.cpp.
|
private |
Definition at line 117 of file franka_combined_hw.cpp.
| bool franka_hw::FrankaCombinedHW::hasError | ( | ) |
Checks whether the robots are in error or reflex mode.
Definition at line 124 of file franka_combined_hw.cpp.
|
overridevirtual |
The init function is called to initialize the CombinedFrankaHW from a non-realtime thread.
| [in] | root_nh | A NodeHandle in the root of the caller namespace. |
| [in] | robot_hw_nh | A NodeHandle in the namespace from which the RobotHW. should read its configuration. |
Reimplemented from combined_robot_hw::CombinedRobotHW.
Definition at line 21 of file franka_combined_hw.cpp.
|
overridevirtual |
Reads data from the robot HW.
| [in] | time | The current time. |
| [in] | period | The time passed since the last call to read. |
Reimplemented from combined_robot_hw::CombinedRobotHW.
Definition at line 96 of file franka_combined_hw.cpp.
|
private |
Definition at line 138 of file franka_combined_hw.cpp.
|
protected |
Definition at line 71 of file franka_combined_hw.h.
|
protected |
Definition at line 72 of file franka_combined_hw.h.
|
protected |
Definition at line 73 of file franka_combined_hw.h.
|
private |
Definition at line 78 of file franka_combined_hw.h.