#include <seed_r7_robot_hardware.h>

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 |
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_ |
Definition at line 71 of file seed_r7_robot_hardware.h.
|
protected |
| Enumerator | |
|---|---|
| EFFORT | |
| POSITION | |
| POSITION_PID | |
| VELOCITY | |
| VELOCITY_PID | |
Definition at line 115 of file seed_r7_robot_hardware.h.
|
protected |
| Enumerator | |
|---|---|
| NONE | |
| PRISMATIC | |
| ROTATIONAL | |
| CONTINUOUS | |
| FIXED | |
Definition at line 116 of file seed_r7_robot_hardware.h.
|
inline |
Definition at line 74 of file seed_r7_robot_hardware.h.
|
inlinevirtual |
Reimplemented from hardware_interface::RobotHW.
Definition at line 76 of file seed_r7_robot_hardware.h.
| void robot_hardware::RobotHW::getBatteryVoltage | ( | const ros::TimerEvent & | _event | ) |
Definition at line 374 of file seed_r7_robot_hardware.cpp.
|
inline |
Definition at line 85 of file seed_r7_robot_hardware.h.
|
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.
|
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.
|
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.
|
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 | ||
| ) |
|
protected |
Definition at line 149 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 159 of file seed_r7_robot_hardware.h.
|
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.
|
protected |
Definition at line 147 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 142 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 141 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 161 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 165 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 144 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 128 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 131 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 134 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 126 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 125 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 155 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 154 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 129 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 132 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 127 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 130 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 133 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 120 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 139 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 151 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 152 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 118 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 148 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 121 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 123 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 137 of file seed_r7_robot_hardware.h.
|
private |
Definition at line 110 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 156 of file seed_r7_robot_hardware.h.
| struct robot_hardware::RobotHW::RobotStatus robot_hardware::RobotHW::robot_status_ |
|
protected |
Definition at line 162 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 138 of file seed_r7_robot_hardware.h.
|
protected |
Definition at line 145 of file seed_r7_robot_hardware.h.