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

#include <fake_joint_driver.h>

Inheritance diagram for FakeJointDriver:
Inheritance graph
[legend]

Public Member Functions

 FakeJointDriver (void)
 
void update (void)
 Update function to call all of the update function of motors. More...
 
 ~FakeJointDriver ()
 
- 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 void doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual bool init (ros::NodeHandle &, ros::NodeHandle &)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual void read (const ros::Time &, const ros::Duration &)
 
virtual void read (const ros::Time &, const ros::Duration &)
 
virtual SwitchState switchResult (const ControllerInfo &) const
 
virtual SwitchState switchResult () const
 
virtual void write (const ros::Time &, const ros::Duration &)
 
virtual void write (const ros::Time &, const ros::Duration &)
 
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)
 

Private Attributes

std::vector< double > act_dis
 
std::vector< double > act_eff
 
std::vector< double > act_vel
 
std::vector< double > cmd_dis
 
std::vector< std::string > exclude_joints_
 
std::vector< std::string > include_joints_
 
std::vector< std::string > joint_names_
 
hardware_interface::JointStateInterface joint_state_interface
 
hardware_interface::PositionJointInterface position_joint_interface
 
bool use_description_
 
hardware_interface::VelocityJointInterface velocity_joint_interface
 

Additional Inherited Members

- Public Types inherited from hardware_interface::RobotHW
enum  SwitchState
 
- Public Attributes inherited from hardware_interface::RobotHW
 DONE
 
 ERROR
 
 ONGOING
 
- 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 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_
 

Detailed Description

Definition at line 14 of file fake_joint_driver.h.

Constructor & Destructor Documentation

◆ FakeJointDriver()

FakeJointDriver::FakeJointDriver ( void  )

Definition at line 16 of file fake_joint_driver.cpp.

◆ ~FakeJointDriver()

FakeJointDriver::~FakeJointDriver ( )

Definition at line 115 of file fake_joint_driver.cpp.

Member Function Documentation

◆ update()

void FakeJointDriver::update ( void  )

Update function to call all of the update function of motors.

Definition at line 122 of file fake_joint_driver.cpp.

Member Data Documentation

◆ act_dis

std::vector<double> FakeJointDriver::act_dis
private

Definition at line 22 of file fake_joint_driver.h.

◆ act_eff

std::vector<double> FakeJointDriver::act_eff
private

Definition at line 24 of file fake_joint_driver.h.

◆ act_vel

std::vector<double> FakeJointDriver::act_vel
private

Definition at line 23 of file fake_joint_driver.h.

◆ cmd_dis

std::vector<double> FakeJointDriver::cmd_dis
private

Definition at line 21 of file fake_joint_driver.h.

◆ exclude_joints_

std::vector<std::string> FakeJointDriver::exclude_joints_
private

Definition at line 29 of file fake_joint_driver.h.

◆ include_joints_

std::vector<std::string> FakeJointDriver::include_joints_
private

Definition at line 28 of file fake_joint_driver.h.

◆ joint_names_

std::vector<std::string> FakeJointDriver::joint_names_
private

Definition at line 26 of file fake_joint_driver.h.

◆ joint_state_interface

hardware_interface::JointStateInterface FakeJointDriver::joint_state_interface
private

Definition at line 17 of file fake_joint_driver.h.

◆ position_joint_interface

hardware_interface::PositionJointInterface FakeJointDriver::position_joint_interface
private

Definition at line 18 of file fake_joint_driver.h.

◆ use_description_

bool FakeJointDriver::use_description_
private

Definition at line 27 of file fake_joint_driver.h.

◆ velocity_joint_interface

hardware_interface::VelocityJointInterface FakeJointDriver::velocity_joint_interface
private

Definition at line 19 of file fake_joint_driver.h.


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


fake_joint_driver
Author(s): Ryosuke Tajima
autogenerated on Fri Jan 27 2023 04:02:52