#include <Quori.hpp>

Public Member Functions | |
| Quori (ros::NodeHandle &nh, const std::vector< SerialDevice::Ptr > &devices) | |
| virtual void | read (const ros::Time &time, const ros::Duration &period) |
| void | write () |
| virtual void | write (const ros::Time &time, const ros::Duration &period) |
| ~Quori () | |
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 bool | init (ros::NodeHandle &, ros::NodeHandle &) |
| virtual bool | prepareSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
| virtual SwitchState | switchResult () const |
| virtual SwitchState | switchResult (const ControllerInfo &) const |
| virtual | ~RobotHW ()=default |
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) |
Private Member Functions | |
| void | on_base_turret_pos_ (const std_msgs::Float32::ConstPtr &msg) |
| void | on_base_vel_status_ (const geometry_msgs::Vector3::ConstPtr &msg) |
Private Attributes | |
| Joint::Ptr | base_angle_ |
| ros::Publisher | base_holo_vel_pub_ |
| Joint::Ptr | base_left_ |
| Joint::Ptr | base_mode_ |
| float | base_offset_ |
| ros::Publisher | base_offset_pub_ |
| Joint::Ptr | base_right_ |
| Joint::Ptr | base_turret_ |
| ros::Subscriber | base_turret_pos_ |
| boost::optional< geometry_msgs::Vector3::ConstPtr > | base_vel_ |
| ros::Publisher | base_vel_pub_ |
| ros::Subscriber | base_vel_status_ |
| Joint::Ptr | base_x_ |
| Joint::Ptr | base_y_ |
| double * | device_joint_buffer_ |
| std::map< SerialDevice::Ptr, std::vector< std::size_t > > | device_joints_ |
| std::map< SerialDevice::Ptr, quori::message::States > | device_states_ |
| std::vector< SerialDevice::Ptr > | devices_ |
| std::unordered_map< std::string, std::size_t > | joint_indices_ |
| std::vector< Joint::Ptr > | joints_ |
| ros::Time | last_read_ |
| std::size_t | max_device_joints_ |
| ros::NodeHandle & | nh_ |
| hardware_interface::PositionJointInterface | position_interface_ |
| hardware_interface::JointStateInterface | state_interface_ |
| hardware_interface::VelocityJointInterface | velocity_interface_ |
Additional Inherited Members | |
Public Types inherited from hardware_interface::RobotHW | |
| enum | SwitchState { SwitchState::DONE, SwitchState::ONGOING, SwitchState::ERROR } |
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 inherited from hardware_interface::InterfaceManager | |
| std::vector< ResourceManagerBase * > | interface_destruction_list_ |
| InterfaceManagerVector | interface_managers_ |
| InterfaceMap | interfaces_ |
| InterfaceMap | interfaces_combo_ |
| SizeMap | num_ifaces_registered_ |
| ResourceMap | resources_ |
| Quori::Quori | ( | ros::NodeHandle & | nh, |
| const std::vector< SerialDevice::Ptr > & | devices | ||
| ) |
|
private |
|
private |
|
virtual |
Reimplemented from hardware_interface::RobotHW.
| void quori_controller::Quori::write | ( | ) |
|
virtual |
Reimplemented from hardware_interface::RobotHW.
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |