Classes | Public Member Functions | Private Attributes | List of all members
FourWheelSteering Class Reference

#include <four_wheel_steering.h>

Inheritance diagram for FourWheelSteering:
Inheritance graph
[legend]

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 void doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual bool init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
virtual void read (const ros::Time &time, const ros::Duration &period)
 
virtual void read (const ros::Time &time, const ros::Duration &period)
 
 RobotHW ()
 
virtual void write (const ros::Time &time, const ros::Duration &period)
 
virtual void write (const ros::Time &time, const ros::Duration &period)
 
virtual ~RobotHW ()
 
- 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 Attributes

hardware_interface::PositionJointInterface jnt_pos_interface_
 
hardware_interface::JointStateInterface jnt_state_interface_
 
hardware_interface::VelocityJointInterface jnt_vel_interface_
 
struct FourWheelSteering::Joint joints_ [4]
 
ros::NodeHandle nh_
 
bool running_
 
ros::ServiceServer start_srv_
 
struct FourWheelSteering::SteeringJoint steering_joints_ [4]
 
ros::ServiceServer stop_srv_
 

Additional Inherited Members

- 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
boost::ptr_vector< ResourceManagerBaseinterface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

Detailed Description

Definition at line 21 of file four_wheel_steering.h.

Constructor & Destructor Documentation

FourWheelSteering::FourWheelSteering ( )
inline

Definition at line 24 of file four_wheel_steering.h.

Member Function Documentation

ros::Duration FourWheelSteering::getPeriod ( ) const
inline

Definition at line 60 of file four_wheel_steering.h.

ros::Time FourWheelSteering::getTime ( ) const
inline

Definition at line 59 of file four_wheel_steering.h.

void FourWheelSteering::read ( )
inline

Definition at line 62 of file four_wheel_steering.h.

bool FourWheelSteering::start_callback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
)
inline

Definition at line 114 of file four_wheel_steering.h.

bool FourWheelSteering::stop_callback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
)
inline

Definition at line 120 of file four_wheel_steering.h.

void FourWheelSteering::write ( )
inline

Definition at line 82 of file four_wheel_steering.h.

Member Data Documentation

hardware_interface::PositionJointInterface FourWheelSteering::jnt_pos_interface_
private

Definition at line 129 of file four_wheel_steering.h.

hardware_interface::JointStateInterface FourWheelSteering::jnt_state_interface_
private

Definition at line 127 of file four_wheel_steering.h.

hardware_interface::VelocityJointInterface FourWheelSteering::jnt_vel_interface_
private

Definition at line 128 of file four_wheel_steering.h.

struct FourWheelSteering::Joint FourWheelSteering::joints_[4]
private
ros::NodeHandle FourWheelSteering::nh_
private

Definition at line 152 of file four_wheel_steering.h.

bool FourWheelSteering::running_
private

Definition at line 150 of file four_wheel_steering.h.

ros::ServiceServer FourWheelSteering::start_srv_
private

Definition at line 153 of file four_wheel_steering.h.

struct FourWheelSteering::SteeringJoint FourWheelSteering::steering_joints_[4]
private
ros::ServiceServer FourWheelSteering::stop_srv_
private

Definition at line 154 of file four_wheel_steering.h.


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


four_wheel_steering_controller
Author(s): Vincent Rousseau
autogenerated on Thu Apr 11 2019 03:08:25