#include <GeomController.h>

Public Types | |
| typedef std::vector< typename Controller::WheelParams > | wheel_params_t |
Public Types inherited from controller_interface::ControllerBase | |
| typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
| enum | ControllerState { ControllerState::CONSTRUCTED, ControllerState::INITIALIZED, ControllerState::RUNNING, ControllerState::STOPPED, ControllerState::WAITING, ControllerState::ABORTED } |
Public Member Functions | |
| bool | init (Interface *hw, const wheel_params_t &wheel_params) |
| bool | init (Interface *hw, ros::NodeHandle &controller_nh) |
Public Member Functions inherited from cob_omni_drive_controller::GeomControllerBase< Interface::ResourceHandleType, Controller > | |
| void | updateState () |
Public Member Functions inherited from controller_interface::Controller< Interface > | |
| virtual bool | init (T *, ros::NodeHandle &) |
| virtual bool | init (T *, ros::NodeHandle &, ros::NodeHandle &) |
Public Member Functions inherited from controller_interface::ControllerBase | |
| virtual void | aborting (const ros::Time &) |
| virtual void | aborting (const ros::Time &) |
| bool | abortRequest (const ros::Time &time) |
| bool | abortRequest (const ros::Time &time) |
| ControllerBase ()=default | |
| ControllerBase (const ControllerBase &)=delete | |
| ControllerBase (ControllerBase &&)=delete | |
| bool | isAborted () const |
| bool | isAborted () const |
| bool | isInitialized () const |
| bool | isInitialized () const |
| bool | isRunning () const |
| bool | isRunning () const |
| bool | isStopped () const |
| bool | isStopped () const |
| bool | isWaiting () const |
| bool | isWaiting () const |
| ControllerBase & | operator= (const ControllerBase &)=delete |
| ControllerBase & | operator= (ControllerBase &&)=delete |
| virtual void | starting (const ros::Time &) |
| virtual void | starting (const ros::Time &) |
| bool | startRequest (const ros::Time &time) |
| bool | startRequest (const ros::Time &time) |
| virtual void | stopping (const ros::Time &) |
| virtual void | stopping (const ros::Time &) |
| bool | stopRequest (const ros::Time &time) |
| bool | stopRequest (const ros::Time &time) |
| virtual void | update (const ros::Time &time, const ros::Duration &period)=0 |
| virtual void | update (const ros::Time &time, const ros::Duration &period)=0 |
| void | updateRequest (const ros::Time &time, const ros::Duration &period) |
| void | updateRequest (const ros::Time &time, const ros::Duration &period) |
| virtual void | waiting (const ros::Time &) |
| virtual void | waiting (const ros::Time &) |
| bool | waitRequest (const ros::Time &time) |
| bool | waitRequest (const ros::Time &time) |
| virtual | ~ControllerBase ()=default |
Additional Inherited Members | |
Public Attributes inherited from controller_interface::ControllerBase | |
| ControllerState | state_ |
Protected Member Functions inherited from cob_omni_drive_controller::GeomControllerBase< Interface::ResourceHandleType, Controller > | |
| bool | setup (const std::vector< typename Controller::WheelParams > &wheel_params) |
Protected Member Functions inherited from controller_interface::Controller< Interface > | |
| std::string | getHardwareInterfaceType () const |
| bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override |
Protected Attributes inherited from cob_omni_drive_controller::GeomControllerBase< Interface::ResourceHandleType, Controller > | |
| std::vector< Interface::ResourceHandleType > | drive_joints_ |
| boost::scoped_ptr< Controller > | geom_ |
| std::vector< Interface::ResourceHandleType > | steer_joints_ |
| std::vector< WheelState > | wheel_states_ |
Definition at line 58 of file GeomController.h.
| typedef std::vector<typename Controller::WheelParams> cob_omni_drive_controller::GeomController< Interface, Controller >::wheel_params_t |
Definition at line 62 of file GeomController.h.
|
inline |
Definition at line 68 of file GeomController.h.
|
inline |
Definition at line 63 of file GeomController.h.