#include <noid_robot_hardware.h>
|
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 () |
|
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 () |
|
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) |
|
|
enum | ControlMethod {
EFFORT,
POSITION,
POSITION_PID,
VELOCITY,
VELOCITY_PID
} |
|
enum | JointType {
NONE,
PRISMATIC,
ROTATIONAL,
CONTINUOUS,
FIXED
} |
|
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 |
|
Definition at line 74 of file noid_robot_hardware.h.
noid_robot_hardware::NoidRobotHW::NoidRobotHW |
( |
| ) |
|
|
inline |
virtual noid_robot_hardware::NoidRobotHW::~NoidRobotHW |
( |
| ) |
|
|
inlinevirtual |
double noid_robot_hardware::NoidRobotHW::getPeriod |
( |
| ) |
|
|
inline |
void noid_robot_hardware::NoidRobotHW::onWheelServo |
( |
bool |
_value | ) |
|
void noid_robot_hardware::NoidRobotHW::readPos |
( |
const ros::Time & |
time, |
|
|
const ros::Duration & |
period, |
|
|
bool |
update |
|
) |
| |
void noid_robot_hardware::NoidRobotHW::runHandScript |
( |
uint8_t |
_number, |
|
|
uint16_t |
_script, |
|
|
uint8_t |
_current |
|
) |
| |
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 | ) |
|
int noid_robot_hardware::NoidRobotHW::BASE_COMMAND_PERIOD_MS_ |
|
protected |
int noid_robot_hardware::NoidRobotHW::CONTROL_PERIOD_US_ |
|
protected |
bool noid_robot_hardware::NoidRobotHW::initialized_flag_ |
|
protected |
std::vector<ControlMethod> noid_robot_hardware::NoidRobotHW::joint_control_methods_ |
|
protected |
std::vector<double> noid_robot_hardware::NoidRobotHW::joint_effort_ |
|
protected |
std::vector<double> noid_robot_hardware::NoidRobotHW::joint_effort_command_ |
|
protected |
std::vector<double> noid_robot_hardware::NoidRobotHW::joint_effort_limits_ |
|
protected |
std::vector<std::string> noid_robot_hardware::NoidRobotHW::joint_list_ |
|
protected |
std::vector<std::string> noid_robot_hardware::NoidRobotHW::joint_names_lower_ |
|
protected |
std::vector<std::string> noid_robot_hardware::NoidRobotHW::joint_names_upper_ |
|
protected |
std::vector<double> noid_robot_hardware::NoidRobotHW::joint_position_ |
|
protected |
std::vector<double> noid_robot_hardware::NoidRobotHW::joint_position_command_ |
|
protected |
std::vector<JointType> noid_robot_hardware::NoidRobotHW::joint_types_ |
|
protected |
std::vector<double> noid_robot_hardware::NoidRobotHW::joint_velocity_ |
|
protected |
std::vector<double> noid_robot_hardware::NoidRobotHW::joint_velocity_command_ |
|
protected |
std::vector<int16_t> noid_robot_hardware::NoidRobotHW::lower_act_strokes_ |
|
protected |
std::mutex noid_robot_hardware::NoidRobotHW::mutex_lower_ |
|
protected |
std::mutex noid_robot_hardware::NoidRobotHW::mutex_upper_ |
|
protected |
unsigned int noid_robot_hardware::NoidRobotHW::number_of_angles_ |
|
protected |
float noid_robot_hardware::NoidRobotHW::OVERLAP_SCALE_ |
|
protected |
std::vector<double> noid_robot_hardware::NoidRobotHW::prev_ref_positions_ |
|
protected |
std::string noid_robot_hardware::NoidRobotHW::robot_model |
|
protected |
std::vector<int16_t> noid_robot_hardware::NoidRobotHW::upper_act_strokes_ |
|
protected |
bool noid_robot_hardware::NoidRobotHW::upper_send_enable_ |
|
protected |
The documentation for this class was generated from the following files: