Public Member Functions | Protected Types | Protected Attributes | List of all members
noid_robot_hardware::NoidRobotHW Class Reference

#include <noid_robot_hardware.h>

Inheritance diagram for noid_robot_hardware::NoidRobotHW:
Inheritance graph
[legend]

Public Member Functions

double getPeriod ()
 
virtual bool init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
 
 NoidRobotHW ()
 
void onWheelServo (bool _value)
 
virtual void read (const ros::Time &time, const ros::Duration &period)
 
void readPos (const ros::Time &time, const ros::Duration &period, bool update)
 
void runHandScript (uint8_t _number, uint16_t _script, uint8_t _current)
 
virtual void write (const ros::Time &time, const ros::Duration &period)
 
void writeWheel (const std::vector< std::string > &_names, const std::vector< int16_t > &_vel, double _tm_sec)
 
void writeWheel (std::vector< int16_t > &_vel)
 
virtual ~NoidRobotHW ()
 
- 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 void doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
 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 Types

enum  ControlMethod {
  EFFORT, POSITION, POSITION_PID, VELOCITY,
  VELOCITY_PID
}
 
enum  JointType {
  NONE, PRISMATIC, ROTATIONAL, CONTINUOUS,
  FIXED
}
 
- 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

int BASE_COMMAND_PERIOD_MS_
 
int CONTROL_PERIOD_US_
 
boost::shared_ptr< NoidLowerControllercontroller_lower_
 
boost::shared_ptr< NoidUpperControllercontroller_upper_
 
bool initialized_flag_
 
std::vector< ControlMethodjoint_control_methods_
 
std::vector< double > joint_effort_
 
std::vector< double > joint_effort_command_
 
std::vector< double > joint_effort_limits_
 
std::vector< std::string > joint_list_
 
std::vector< std::string > joint_names_lower_
 
std::vector< std::string > joint_names_upper_
 
std::vector< double > joint_position_
 
std::vector< double > joint_position_command_
 
std::vector< JointTypejoint_types_
 
std::vector< double > joint_velocity_
 
std::vector< double > joint_velocity_command_
 
hardware_interface::JointStateInterface js_interface_
 
std::vector< int16_t > lower_act_strokes_
 
std::mutex mutex_lower_
 
std::mutex mutex_upper_
 
unsigned int number_of_angles_
 
float OVERLAP_SCALE_
 
hardware_interface::PositionJointInterface pj_interface_
 
joint_limits_interface::PositionJointSaturationInterface pj_sat_interface_
 
std::vector< double > prev_ref_positions_
 
std::string robot_model
 
std::vector< int16_t > upper_act_strokes_
 
bool upper_send_enable_
 
- 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_
 

Detailed Description

Definition at line 74 of file noid_robot_hardware.h.

Member Enumeration Documentation

Enumerator
EFFORT 
POSITION 
POSITION_PID 
VELOCITY 
VELOCITY_PID 

Definition at line 99 of file noid_robot_hardware.h.

Enumerator
NONE 
PRISMATIC 
ROTATIONAL 
CONTINUOUS 
FIXED 

Definition at line 100 of file noid_robot_hardware.h.

Constructor & Destructor Documentation

noid_robot_hardware::NoidRobotHW::NoidRobotHW ( )
inline

Definition at line 77 of file noid_robot_hardware.h.

virtual noid_robot_hardware::NoidRobotHW::~NoidRobotHW ( )
inlinevirtual

Definition at line 79 of file noid_robot_hardware.h.

Member Function Documentation

double noid_robot_hardware::NoidRobotHW::getPeriod ( )
inline

Definition at line 87 of file noid_robot_hardware.h.

bool noid_robot_hardware::NoidRobotHW::init ( ros::NodeHandle root_nh,
ros::NodeHandle robot_hw_nh 
)
virtual

initial

Reimplemented from hardware_interface::RobotHW.

Definition at line 47 of file noid_robot_hardware.cpp.

void noid_robot_hardware::NoidRobotHW::onWheelServo ( bool  _value)

Definition at line 330 of file noid_robot_hardware.cpp.

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

Reimplemented from hardware_interface::RobotHW.

Definition at line 217 of file noid_robot_hardware.cpp.

void noid_robot_hardware::NoidRobotHW::readPos ( const ros::Time time,
const ros::Duration period,
bool  update 
)

Definition at line 158 of file noid_robot_hardware.cpp.

void noid_robot_hardware::NoidRobotHW::runHandScript ( uint8_t  _number,
uint16_t  _script,
uint8_t  _current 
)

Definition at line 310 of file noid_robot_hardware.cpp.

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

Reimplemented from hardware_interface::RobotHW.

Definition at line 222 of file noid_robot_hardware.cpp.

void noid_robot_hardware::NoidRobotHW::writeWheel ( const std::vector< std::string > &  _names,
const std::vector< int16_t > &  _vel,
double  _tm_sec 
)
void noid_robot_hardware::NoidRobotHW::writeWheel ( std::vector< int16_t > &  _vel)

Definition at line 323 of file noid_robot_hardware.cpp.

Member Data Documentation

int noid_robot_hardware::NoidRobotHW::BASE_COMMAND_PERIOD_MS_
protected

Definition at line 133 of file noid_robot_hardware.h.

int noid_robot_hardware::NoidRobotHW::CONTROL_PERIOD_US_
protected

Definition at line 131 of file noid_robot_hardware.h.

boost::shared_ptr<NoidLowerController> noid_robot_hardware::NoidRobotHW::controller_lower_
protected

Definition at line 126 of file noid_robot_hardware.h.

boost::shared_ptr<NoidUpperController> noid_robot_hardware::NoidRobotHW::controller_upper_
protected

Definition at line 125 of file noid_robot_hardware.h.

bool noid_robot_hardware::NoidRobotHW::initialized_flag_
protected

Definition at line 128 of file noid_robot_hardware.h.

std::vector<ControlMethod> noid_robot_hardware::NoidRobotHW::joint_control_methods_
protected

Definition at line 112 of file noid_robot_hardware.h.

std::vector<double> noid_robot_hardware::NoidRobotHW::joint_effort_
protected

Definition at line 115 of file noid_robot_hardware.h.

std::vector<double> noid_robot_hardware::NoidRobotHW::joint_effort_command_
protected

Definition at line 118 of file noid_robot_hardware.h.

std::vector<double> noid_robot_hardware::NoidRobotHW::joint_effort_limits_
protected

Definition at line 110 of file noid_robot_hardware.h.

std::vector<std::string> noid_robot_hardware::NoidRobotHW::joint_list_
protected

Definition at line 109 of file noid_robot_hardware.h.

std::vector<std::string> noid_robot_hardware::NoidRobotHW::joint_names_lower_
protected

Definition at line 139 of file noid_robot_hardware.h.

std::vector<std::string> noid_robot_hardware::NoidRobotHW::joint_names_upper_
protected

Definition at line 138 of file noid_robot_hardware.h.

std::vector<double> noid_robot_hardware::NoidRobotHW::joint_position_
protected

Definition at line 113 of file noid_robot_hardware.h.

std::vector<double> noid_robot_hardware::NoidRobotHW::joint_position_command_
protected

Definition at line 116 of file noid_robot_hardware.h.

std::vector<JointType> noid_robot_hardware::NoidRobotHW::joint_types_
protected

Definition at line 111 of file noid_robot_hardware.h.

std::vector<double> noid_robot_hardware::NoidRobotHW::joint_velocity_
protected

Definition at line 114 of file noid_robot_hardware.h.

std::vector<double> noid_robot_hardware::NoidRobotHW::joint_velocity_command_
protected

Definition at line 117 of file noid_robot_hardware.h.

hardware_interface::JointStateInterface noid_robot_hardware::NoidRobotHW::js_interface_
protected

Definition at line 104 of file noid_robot_hardware.h.

std::vector<int16_t> noid_robot_hardware::NoidRobotHW::lower_act_strokes_
protected

Definition at line 123 of file noid_robot_hardware.h.

std::mutex noid_robot_hardware::NoidRobotHW::mutex_lower_
protected

Definition at line 135 of file noid_robot_hardware.h.

std::mutex noid_robot_hardware::NoidRobotHW::mutex_upper_
protected

Definition at line 136 of file noid_robot_hardware.h.

unsigned int noid_robot_hardware::NoidRobotHW::number_of_angles_
protected

Definition at line 102 of file noid_robot_hardware.h.

float noid_robot_hardware::NoidRobotHW::OVERLAP_SCALE_
protected

Definition at line 132 of file noid_robot_hardware.h.

hardware_interface::PositionJointInterface noid_robot_hardware::NoidRobotHW::pj_interface_
protected

Definition at line 105 of file noid_robot_hardware.h.

joint_limits_interface::PositionJointSaturationInterface noid_robot_hardware::NoidRobotHW::pj_sat_interface_
protected

Definition at line 107 of file noid_robot_hardware.h.

std::vector<double> noid_robot_hardware::NoidRobotHW::prev_ref_positions_
protected

Definition at line 121 of file noid_robot_hardware.h.

std::string noid_robot_hardware::NoidRobotHW::robot_model
protected

Definition at line 140 of file noid_robot_hardware.h.

std::vector<int16_t> noid_robot_hardware::NoidRobotHW::upper_act_strokes_
protected

Definition at line 122 of file noid_robot_hardware.h.

bool noid_robot_hardware::NoidRobotHW::upper_send_enable_
protected

Definition at line 129 of file noid_robot_hardware.h.


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


noid_ros_controller
Author(s): Yohei Kakiuchi
autogenerated on Sat Jul 20 2019 03:44:30