Public Types | Public Member Functions | List of all members
cob_omni_drive_controller::GeomController< Interface, Controller > Class Template Reference

#include <GeomController.h>

Inheritance diagram for cob_omni_drive_controller::GeomController< Interface, Controller >:
Inheritance graph
[legend]

Public Types

typedef std::vector< typename Controller::WheelParams > wheel_params_t
 
- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 

Public Member Functions

bool init (Interface *hw, ros::NodeHandle &controller_nh)
 
bool init (Interface *hw, const wheel_params_t &wheel_params)
 
- Public Member Functions inherited from cob_omni_drive_controller::GeomControllerBase< Interface::ResourceHandleType, Controller >
void updateState ()
 
- Public Member Functions inherited from controller_interface::Controller< Interface >
 Controller ()
 
virtual bool init (Interface *, ros::NodeHandle &, ros::NodeHandle &)
 
virtual ~Controller ()
 
- Public Member Functions inherited from controller_interface::ControllerBase
 ControllerBase ()
 
bool isRunning ()
 
bool isRunning ()
 
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 ~ControllerBase ()
 

Additional Inherited Members

- Public Attributes inherited from controller_interface::ControllerBase
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  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
 
virtual bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources)
 
- 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< WheelStatewheel_states_
 

Detailed Description

template<typename Interface, typename Controller>
class cob_omni_drive_controller::GeomController< Interface, Controller >

Definition at line 58 of file GeomController.h.

Member Typedef Documentation

template<typename Interface, typename Controller>
typedef std::vector<typename Controller::WheelParams> cob_omni_drive_controller::GeomController< Interface, Controller >::wheel_params_t

Definition at line 62 of file GeomController.h.

Member Function Documentation

template<typename Interface, typename Controller>
bool cob_omni_drive_controller::GeomController< Interface, Controller >::init ( Interface *  hw,
ros::NodeHandle controller_nh 
)
inlinevirtual

Reimplemented from controller_interface::Controller< Interface >.

Definition at line 63 of file GeomController.h.

template<typename Interface, typename Controller>
bool cob_omni_drive_controller::GeomController< Interface, Controller >::init ( Interface *  hw,
const wheel_params_t wheel_params 
)
inline

Definition at line 68 of file GeomController.h.


The documentation for this class was generated from the following file:


cob_omni_drive_controller
Author(s): Christian Connette, Mathias Lüdtke
autogenerated on Thu Apr 8 2021 02:39:52