#include <four_wheel_steering.h>

Classes | |
| struct | Joint |
| struct | SteeringJoint |
Public Member Functions | |
| FourWheelSteering () | |
| ros::Duration | getPeriod () const |
| ros::Time | getTime () const |
| void | read () |
| bool | start_callback (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
| bool | stop_callback (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
| void | write () |
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 void | read (const ros::Time &, const ros::Duration &) |
| virtual void | read (const ros::Time &, const ros::Duration &) |
| virtual SwitchState | switchResult () const |
| virtual SwitchState | switchResult (const ControllerInfo &) const |
| virtual void | write (const ros::Time &, const ros::Duration &) |
| virtual void | write (const ros::Time &, const ros::Duration &) |
| 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) |
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_ |
Definition at line 24 of file four_wheel_steering.h.
|
inline |
Definition at line 27 of file four_wheel_steering.h.
|
inline |
Definition at line 63 of file four_wheel_steering.h.
|
inline |
Definition at line 62 of file four_wheel_steering.h.
|
inline |
Definition at line 65 of file four_wheel_steering.h.
|
inline |
Definition at line 120 of file four_wheel_steering.h.
|
inline |
Definition at line 126 of file four_wheel_steering.h.
|
inline |
Definition at line 98 of file four_wheel_steering.h.
|
private |
Definition at line 135 of file four_wheel_steering.h.
|
private |
Definition at line 133 of file four_wheel_steering.h.
|
private |
Definition at line 134 of file four_wheel_steering.h.
|
private |
|
private |
Definition at line 158 of file four_wheel_steering.h.
|
private |
Definition at line 156 of file four_wheel_steering.h.
|
private |
Definition at line 159 of file four_wheel_steering.h.
|
private |
|
private |
Definition at line 160 of file four_wheel_steering.h.