#include <seed_r7_robot_hardware.h>
|
| 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 () |
| |
| 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 | prepareSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
| |
| virtual SwitchState | switchResult (const ControllerInfo &) const |
| |
| virtual SwitchState | switchResult () const |
| |
| 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 |
| |
|
| bool | resetRobotStatusCallback (seed_r7_ros_controller::ResetRobotStatus::Request &_req, seed_r7_ros_controller::ResetRobotStatus::Response &_res) |
| |
Definition at line 71 of file seed_r7_robot_hardware.h.
◆ ControlMethod
◆ JointType
◆ RobotHW()
| robot_hardware::RobotHW::RobotHW |
( |
| ) |
|
|
inline |
◆ ~RobotHW()
| virtual robot_hardware::RobotHW::~RobotHW |
( |
| ) |
|
|
inlinevirtual |
◆ getBatteryVoltage()
| void robot_hardware::RobotHW::getBatteryVoltage |
( |
const ros::TimerEvent & |
_event | ) |
|
◆ getPeriod()
| double robot_hardware::RobotHW::getPeriod |
( |
| ) |
|
|
inline |
◆ init()
◆ onWheelServo()
| void robot_hardware::RobotHW::onWheelServo |
( |
bool |
_value | ) |
|
◆ read()
◆ readPos()
◆ resetRobotStatusCallback()
| bool robot_hardware::RobotHW::resetRobotStatusCallback |
( |
seed_r7_ros_controller::ResetRobotStatus::Request & |
_req, |
|
|
seed_r7_ros_controller::ResetRobotStatus::Response & |
_res |
|
) |
| |
|
private |
◆ runHandScript()
| void robot_hardware::RobotHW::runHandScript |
( |
uint8_t |
_number, |
|
|
uint16_t |
_script, |
|
|
uint8_t |
_current |
|
) |
| |
◆ runLedScript()
| void robot_hardware::RobotHW::runLedScript |
( |
uint8_t |
_number, |
|
|
uint16_t |
_script |
|
) |
| |
◆ setDiagnostics()
| void robot_hardware::RobotHW::setDiagnostics |
( |
diagnostic_updater::DiagnosticStatusWrapper & |
stat | ) |
|
◆ setRobotStatus()
| void robot_hardware::RobotHW::setRobotStatus |
( |
| ) |
|
◆ turnWheel()
| void robot_hardware::RobotHW::turnWheel |
( |
std::vector< int16_t > & |
_vel | ) |
|
◆ write()
◆ writeWheel()
| void robot_hardware::RobotHW::writeWheel |
( |
const std::vector< std::string > & |
_names, |
|
|
const std::vector< int16_t > & |
_vel, |
|
|
double |
_tm_sec |
|
) |
| |
◆ BASE_COMMAND_PERIOD_MS_
| int robot_hardware::RobotHW::BASE_COMMAND_PERIOD_MS_ |
|
protected |
◆ bat_vol_pub_
◆ bat_vol_timer_
| ros::Timer robot_hardware::RobotHW::bat_vol_timer_ |
|
protected |
◆ comm_err_
| bool robot_hardware::RobotHW::comm_err_ |
◆ CONTROL_PERIOD_US_
| int robot_hardware::RobotHW::CONTROL_PERIOD_US_ |
|
protected |
◆ controller_lower_
◆ controller_upper_
◆ converter_loader_
◆ diagnostic_updater_
| diagnostic_updater::Updater robot_hardware::RobotHW::diagnostic_updater_ |
|
protected |
◆ initialized_flag_
| bool robot_hardware::RobotHW::initialized_flag_ |
|
protected |
◆ joint_control_methods_
| std::vector<ControlMethod> robot_hardware::RobotHW::joint_control_methods_ |
|
protected |
◆ joint_effort_
| std::vector<double> robot_hardware::RobotHW::joint_effort_ |
|
protected |
◆ joint_effort_command_
| std::vector<double> robot_hardware::RobotHW::joint_effort_command_ |
|
protected |
◆ joint_effort_limits_
| std::vector<double> robot_hardware::RobotHW::joint_effort_limits_ |
|
protected |
◆ joint_list_
| std::vector<std::string> robot_hardware::RobotHW::joint_list_ |
|
protected |
◆ joint_names_lower_
| std::vector<std::string> robot_hardware::RobotHW::joint_names_lower_ |
|
protected |
◆ joint_names_upper_
| std::vector<std::string> robot_hardware::RobotHW::joint_names_upper_ |
|
protected |
◆ joint_position_
| std::vector<double> robot_hardware::RobotHW::joint_position_ |
|
protected |
◆ joint_position_command_
| std::vector<double> robot_hardware::RobotHW::joint_position_command_ |
|
protected |
◆ joint_types_
| std::vector<JointType> robot_hardware::RobotHW::joint_types_ |
|
protected |
◆ joint_velocity_
| std::vector<double> robot_hardware::RobotHW::joint_velocity_ |
|
protected |
◆ joint_velocity_command_
| std::vector<double> robot_hardware::RobotHW::joint_velocity_command_ |
|
protected |
◆ js_interface_
◆ lower_act_strokes_
| std::vector<int16_t> robot_hardware::RobotHW::lower_act_strokes_ |
|
protected |
◆ mutex_lower_
| std::mutex robot_hardware::RobotHW::mutex_lower_ |
|
protected |
◆ mutex_upper_
| std::mutex robot_hardware::RobotHW::mutex_upper_ |
|
protected |
◆ number_of_angles_
| unsigned int robot_hardware::RobotHW::number_of_angles_ |
|
protected |
◆ OVERLAP_SCALE_
| float robot_hardware::RobotHW::OVERLAP_SCALE_ |
|
protected |
◆ pj_interface_
◆ pj_sat_interface_
◆ prev_ref_strokes_
| std::vector<double> robot_hardware::RobotHW::prev_ref_strokes_ |
|
protected |
◆ reset_robot_status_server_
◆ robot_model_plugin_
| std::string robot_hardware::RobotHW::robot_model_plugin_ |
|
protected |
◆ robot_status_
◆ stroke_converter_
◆ upper_act_strokes_
| std::vector<int16_t> robot_hardware::RobotHW::upper_act_strokes_ |
|
protected |
◆ upper_send_enable_
| bool robot_hardware::RobotHW::upper_send_enable_ |
|
protected |
The documentation for this class was generated from the following files: