Classes | Public Member Functions | Public Attributes | Protected Types | Protected Attributes | Private Member Functions | Private Attributes | List of all members
robot_hardware::RobotHW Class Reference

#include <seed_r7_robot_hardware.h>

Inheritance diagram for robot_hardware::RobotHW:
Inheritance graph
[legend]

Classes

struct  RobotStatus
 

Public Member Functions

void getBatteryVoltage (const ros::TimerEvent &_event)
 
double getPeriod ()
 
virtual bool init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
 
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)
 
 RobotHW ()
 
void runHandScript (uint8_t _number, uint16_t _script, uint8_t _current)
 
void runLedScript (uint8_t _number, uint16_t _script)
 
void setDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
void setRobotStatus ()
 
void turnWheel (std::vector< int16_t > &_vel)
 
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)
 
virtual ~RobotHW ()
 
- 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 ()
 
- 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)
 

Public Attributes

bool comm_err_
 
struct robot_hardware::RobotHW::RobotStatus robot_status_
 

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_
 
ros::Publisher bat_vol_pub_
 
ros::Timer bat_vol_timer_
 
int CONTROL_PERIOD_US_
 
boost::shared_ptr< robot_hardware::LowerControllercontroller_lower_
 
boost::shared_ptr< robot_hardware::UpperControllercontroller_upper_
 
pluginlib::ClassLoader< seed_converter::StrokeConverterconverter_loader_
 
diagnostic_updater::Updater diagnostic_updater_
 
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_strokes_
 
std::string robot_model_plugin_
 
boost::shared_ptr< seed_converter::StrokeConverterstroke_converter_
 
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_
 

Private Member Functions

bool resetRobotStatusCallback (seed_r7_ros_controller::ResetRobotStatus::Request &_req, seed_r7_ros_controller::ResetRobotStatus::Response &_res)
 

Private Attributes

ros::ServiceServer reset_robot_status_server_
 

Detailed Description

Definition at line 71 of file seed_r7_robot_hardware.h.

Member Enumeration Documentation

Enumerator
EFFORT 
POSITION 
POSITION_PID 
VELOCITY 
VELOCITY_PID 

Definition at line 115 of file seed_r7_robot_hardware.h.

Enumerator
NONE 
PRISMATIC 
ROTATIONAL 
CONTINUOUS 
FIXED 

Definition at line 116 of file seed_r7_robot_hardware.h.

Constructor & Destructor Documentation

robot_hardware::RobotHW::RobotHW ( )
inline

Definition at line 74 of file seed_r7_robot_hardware.h.

virtual robot_hardware::RobotHW::~RobotHW ( )
inlinevirtual

Reimplemented from hardware_interface::RobotHW.

Definition at line 76 of file seed_r7_robot_hardware.h.

Member Function Documentation

void robot_hardware::RobotHW::getBatteryVoltage ( const ros::TimerEvent _event)

Definition at line 374 of file seed_r7_robot_hardware.cpp.

double robot_hardware::RobotHW::getPeriod ( )
inline

Definition at line 85 of file seed_r7_robot_hardware.h.

bool robot_hardware::RobotHW::init ( ros::NodeHandle root_nh,
ros::NodeHandle robot_hw_nh 
)
virtual

Reimplemented from hardware_interface::RobotHW.

Definition at line 43 of file seed_r7_robot_hardware.cpp.

void robot_hardware::RobotHW::onWheelServo ( bool  _value)

Definition at line 367 of file seed_r7_robot_hardware.cpp.

void robot_hardware::RobotHW::read ( const ros::Time time,
const ros::Duration period 
)
virtual

Reimplemented from hardware_interface::RobotHW.

Definition at line 254 of file seed_r7_robot_hardware.cpp.

void robot_hardware::RobotHW::readPos ( const ros::Time time,
const ros::Duration period,
bool  update 
)

Definition at line 190 of file seed_r7_robot_hardware.cpp.

bool robot_hardware::RobotHW::resetRobotStatusCallback ( seed_r7_ros_controller::ResetRobotStatus::Request &  _req,
seed_r7_ros_controller::ResetRobotStatus::Response &  _res 
)
private

Definition at line 472 of file seed_r7_robot_hardware.cpp.

void robot_hardware::RobotHW::runHandScript ( uint8_t  _number,
uint16_t  _script,
uint8_t  _current 
)

Definition at line 347 of file seed_r7_robot_hardware.cpp.

void robot_hardware::RobotHW::runLedScript ( uint8_t  _number,
uint16_t  _script 
)

Definition at line 385 of file seed_r7_robot_hardware.cpp.

void robot_hardware::RobotHW::setDiagnostics ( diagnostic_updater::DiagnosticStatusWrapper &  stat)

Definition at line 424 of file seed_r7_robot_hardware.cpp.

void robot_hardware::RobotHW::setRobotStatus ( )

Definition at line 392 of file seed_r7_robot_hardware.cpp.

void robot_hardware::RobotHW::turnWheel ( std::vector< int16_t > &  _vel)

Definition at line 360 of file seed_r7_robot_hardware.cpp.

void robot_hardware::RobotHW::write ( const ros::Time time,
const ros::Duration period 
)
virtual

Reimplemented from hardware_interface::RobotHW.

Definition at line 259 of file seed_r7_robot_hardware.cpp.

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

Member Data Documentation

int robot_hardware::RobotHW::BASE_COMMAND_PERIOD_MS_
protected

Definition at line 149 of file seed_r7_robot_hardware.h.

ros::Publisher robot_hardware::RobotHW::bat_vol_pub_
protected

Definition at line 159 of file seed_r7_robot_hardware.h.

ros::Timer robot_hardware::RobotHW::bat_vol_timer_
protected

Definition at line 158 of file seed_r7_robot_hardware.h.

bool robot_hardware::RobotHW::comm_err_

Definition at line 97 of file seed_r7_robot_hardware.h.

int robot_hardware::RobotHW::CONTROL_PERIOD_US_
protected

Definition at line 147 of file seed_r7_robot_hardware.h.

boost::shared_ptr<robot_hardware::LowerController> robot_hardware::RobotHW::controller_lower_
protected

Definition at line 142 of file seed_r7_robot_hardware.h.

boost::shared_ptr<robot_hardware::UpperController> robot_hardware::RobotHW::controller_upper_
protected

Definition at line 141 of file seed_r7_robot_hardware.h.

pluginlib::ClassLoader<seed_converter::StrokeConverter> robot_hardware::RobotHW::converter_loader_
protected

Definition at line 161 of file seed_r7_robot_hardware.h.

diagnostic_updater::Updater robot_hardware::RobotHW::diagnostic_updater_
protected

Definition at line 165 of file seed_r7_robot_hardware.h.

bool robot_hardware::RobotHW::initialized_flag_
protected

Definition at line 144 of file seed_r7_robot_hardware.h.

std::vector<ControlMethod> robot_hardware::RobotHW::joint_control_methods_
protected

Definition at line 128 of file seed_r7_robot_hardware.h.

std::vector<double> robot_hardware::RobotHW::joint_effort_
protected

Definition at line 131 of file seed_r7_robot_hardware.h.

std::vector<double> robot_hardware::RobotHW::joint_effort_command_
protected

Definition at line 134 of file seed_r7_robot_hardware.h.

std::vector<double> robot_hardware::RobotHW::joint_effort_limits_
protected

Definition at line 126 of file seed_r7_robot_hardware.h.

std::vector<std::string> robot_hardware::RobotHW::joint_list_
protected

Definition at line 125 of file seed_r7_robot_hardware.h.

std::vector<std::string> robot_hardware::RobotHW::joint_names_lower_
protected

Definition at line 155 of file seed_r7_robot_hardware.h.

std::vector<std::string> robot_hardware::RobotHW::joint_names_upper_
protected

Definition at line 154 of file seed_r7_robot_hardware.h.

std::vector<double> robot_hardware::RobotHW::joint_position_
protected

Definition at line 129 of file seed_r7_robot_hardware.h.

std::vector<double> robot_hardware::RobotHW::joint_position_command_
protected

Definition at line 132 of file seed_r7_robot_hardware.h.

std::vector<JointType> robot_hardware::RobotHW::joint_types_
protected

Definition at line 127 of file seed_r7_robot_hardware.h.

std::vector<double> robot_hardware::RobotHW::joint_velocity_
protected

Definition at line 130 of file seed_r7_robot_hardware.h.

std::vector<double> robot_hardware::RobotHW::joint_velocity_command_
protected

Definition at line 133 of file seed_r7_robot_hardware.h.

hardware_interface::JointStateInterface robot_hardware::RobotHW::js_interface_
protected

Definition at line 120 of file seed_r7_robot_hardware.h.

std::vector<int16_t> robot_hardware::RobotHW::lower_act_strokes_
protected

Definition at line 139 of file seed_r7_robot_hardware.h.

std::mutex robot_hardware::RobotHW::mutex_lower_
protected

Definition at line 151 of file seed_r7_robot_hardware.h.

std::mutex robot_hardware::RobotHW::mutex_upper_
protected

Definition at line 152 of file seed_r7_robot_hardware.h.

unsigned int robot_hardware::RobotHW::number_of_angles_
protected

Definition at line 118 of file seed_r7_robot_hardware.h.

float robot_hardware::RobotHW::OVERLAP_SCALE_
protected

Definition at line 148 of file seed_r7_robot_hardware.h.

hardware_interface::PositionJointInterface robot_hardware::RobotHW::pj_interface_
protected

Definition at line 121 of file seed_r7_robot_hardware.h.

joint_limits_interface::PositionJointSaturationInterface robot_hardware::RobotHW::pj_sat_interface_
protected

Definition at line 123 of file seed_r7_robot_hardware.h.

std::vector<double> robot_hardware::RobotHW::prev_ref_strokes_
protected

Definition at line 137 of file seed_r7_robot_hardware.h.

ros::ServiceServer robot_hardware::RobotHW::reset_robot_status_server_
private

Definition at line 110 of file seed_r7_robot_hardware.h.

std::string robot_hardware::RobotHW::robot_model_plugin_
protected

Definition at line 156 of file seed_r7_robot_hardware.h.

struct robot_hardware::RobotHW::RobotStatus robot_hardware::RobotHW::robot_status_
boost::shared_ptr<seed_converter::StrokeConverter> robot_hardware::RobotHW::stroke_converter_
protected

Definition at line 162 of file seed_r7_robot_hardware.h.

std::vector<int16_t> robot_hardware::RobotHW::upper_act_strokes_
protected

Definition at line 138 of file seed_r7_robot_hardware.h.

bool robot_hardware::RobotHW::upper_send_enable_
protected

Definition at line 145 of file seed_r7_robot_hardware.h.


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


seed_r7_ros_controller
Author(s): Yohei Kakiuchi
autogenerated on Sun Apr 18 2021 02:40:34