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

#include <ackermann_steering_bot.h>

Inheritance diagram for AckermannSteeringBot:
Inheritance graph
[legend]

Public Member Functions

 AckermannSteeringBot ()
 
ros::Duration getPeriod () const
 
ros::Time getTime () const
 
void read ()
 
bool startCallback (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
 
bool stopCallback (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 ControllerInfo &) const
 
virtual SwitchState switchResult () 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)
 

Private Member Functions

void cleanUp ()
 
void getJointNames (ros::NodeHandle &_nh)
 
void getSteerJointNames (ros::NodeHandle &_nh)
 
void getWheelJointNames (ros::NodeHandle &_nh)
 
void registerCommandJointInterfaceHandle (hardware_interface::JointStateInterface &_jnt_state_interface, hardware_interface::JointCommandInterface &_jnt_cmd_interface, const std::string _jnt_name, double &_jnt_cmd)
 
void registerHardwareInterfaces ()
 
void registerInterfaceHandles (hardware_interface::JointStateInterface &_jnt_state_interface, hardware_interface::JointCommandInterface &_jnt_cmd_interface, const std::string _jnt_name, double &_jnt_pos, double &_jnt_vel, double &_jnt_eff, double &_jnt_cmd)
 
void registerJointStateInterfaceHandle (hardware_interface::JointStateInterface &_jnt_state_interface, const std::string _jnt_name, double &_jnt_pos, double &_jnt_vel, double &_jnt_eff)
 
void registerSteerInterface ()
 
void registerWheelInterface ()
 

Private Attributes

double front_steer_jnt_eff_
 
std::string front_steer_jnt_name_
 
double front_steer_jnt_pos_
 
double front_steer_jnt_pos_cmd_
 
hardware_interface::PositionJointInterface front_steer_jnt_pos_cmd_interface_
 
double front_steer_jnt_vel_
 
hardware_interface::JointStateInterface jnt_state_interface_
 
ros::NodeHandle nh_
 
std::string ns_
 
double rear_wheel_jnt_eff_
 
std::string rear_wheel_jnt_name_
 
double rear_wheel_jnt_pos_
 
double rear_wheel_jnt_vel_
 
double rear_wheel_jnt_vel_cmd_
 
hardware_interface::VelocityJointInterface rear_wheel_jnt_vel_cmd_interface_
 
bool running_
 
ros::ServiceServer start_srv_
 
ros::ServiceServer stop_srv_
 
std::vector< double > virtual_front_steer_jnt_eff_
 
std::vector< std::string > virtual_front_steer_jnt_names_
 
std::vector< double > virtual_front_steer_jnt_pos_
 
std::vector< double > virtual_front_steer_jnt_pos_cmd_
 
std::vector< double > virtual_front_steer_jnt_vel_
 
std::vector< double > virtual_front_wheel_jnt_eff_
 
std::vector< std::string > virtual_front_wheel_jnt_names_
 
std::vector< double > virtual_front_wheel_jnt_pos_
 
std::vector< double > virtual_front_wheel_jnt_vel_
 
std::vector< double > virtual_front_wheel_jnt_vel_cmd_
 
std::vector< double > virtual_rear_wheel_jnt_eff_
 
std::vector< std::string > virtual_rear_wheel_jnt_names_
 
std::vector< double > virtual_rear_wheel_jnt_pos_
 
std::vector< double > virtual_rear_wheel_jnt_vel_
 
std::vector< double > virtual_rear_wheel_jnt_vel_cmd_
 
double wheel_separation_h_
 
double wheel_separation_w_
 

Additional Inherited Members

- Public Types inherited from hardware_interface::RobotHW
enum  SwitchState
 
- Public Attributes inherited from hardware_interface::RobotHW
 DONE
 
 ERROR
 
 ONGOING
 
- 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_
 

Detailed Description

Definition at line 58 of file ackermann_steering_bot.h.

Constructor & Destructor Documentation

◆ AckermannSteeringBot()

AckermannSteeringBot::AckermannSteeringBot ( )
inline

Definition at line 61 of file ackermann_steering_bot.h.

Member Function Documentation

◆ cleanUp()

void AckermannSteeringBot::cleanUp ( )
inlineprivate

Definition at line 204 of file ackermann_steering_bot.h.

◆ getJointNames()

void AckermannSteeringBot::getJointNames ( ros::NodeHandle _nh)
inlineprivate

Definition at line 242 of file ackermann_steering_bot.h.

◆ getPeriod()

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

Definition at line 79 of file ackermann_steering_bot.h.

◆ getSteerJointNames()

void AckermannSteeringBot::getSteerJointNames ( ros::NodeHandle _nh)
inlineprivate

Definition at line 269 of file ackermann_steering_bot.h.

◆ getTime()

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

Definition at line 78 of file ackermann_steering_bot.h.

◆ getWheelJointNames()

void AckermannSteeringBot::getWheelJointNames ( ros::NodeHandle _nh)
inlineprivate

Definition at line 248 of file ackermann_steering_bot.h.

◆ read()

void AckermannSteeringBot::read ( )
inline

Definition at line 81 of file ackermann_steering_bot.h.

◆ registerCommandJointInterfaceHandle()

void AckermannSteeringBot::registerCommandJointInterfaceHandle ( hardware_interface::JointStateInterface _jnt_state_interface,
hardware_interface::JointCommandInterface _jnt_cmd_interface,
const std::string  _jnt_name,
double &  _jnt_cmd 
)
inlineprivate

Definition at line 359 of file ackermann_steering_bot.h.

◆ registerHardwareInterfaces()

void AckermannSteeringBot::registerHardwareInterfaces ( )
inlineprivate

Definition at line 284 of file ackermann_steering_bot.h.

◆ registerInterfaceHandles()

void AckermannSteeringBot::registerInterfaceHandles ( hardware_interface::JointStateInterface _jnt_state_interface,
hardware_interface::JointCommandInterface _jnt_cmd_interface,
const std::string  _jnt_name,
double &  _jnt_pos,
double &  _jnt_vel,
double &  _jnt_eff,
double &  _jnt_cmd 
)
inlineprivate

Definition at line 334 of file ackermann_steering_bot.h.

◆ registerJointStateInterfaceHandle()

void AckermannSteeringBot::registerJointStateInterfaceHandle ( hardware_interface::JointStateInterface _jnt_state_interface,
const std::string  _jnt_name,
double &  _jnt_pos,
double &  _jnt_vel,
double &  _jnt_eff 
)
inlineprivate

Definition at line 346 of file ackermann_steering_bot.h.

◆ registerSteerInterface()

void AckermannSteeringBot::registerSteerInterface ( )
inlineprivate

Definition at line 318 of file ackermann_steering_bot.h.

◆ registerWheelInterface()

void AckermannSteeringBot::registerWheelInterface ( )
inlineprivate

Definition at line 295 of file ackermann_steering_bot.h.

◆ startCallback()

bool AckermannSteeringBot::startCallback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
)
inline

Definition at line 188 of file ackermann_steering_bot.h.

◆ stopCallback()

bool AckermannSteeringBot::stopCallback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
)
inline

Definition at line 195 of file ackermann_steering_bot.h.

◆ write()

void AckermannSteeringBot::write ( )
inline

Definition at line 155 of file ackermann_steering_bot.h.

Member Data Documentation

◆ front_steer_jnt_eff_

double AckermannSteeringBot::front_steer_jnt_eff_
private

Definition at line 414 of file ackermann_steering_bot.h.

◆ front_steer_jnt_name_

std::string AckermannSteeringBot::front_steer_jnt_name_
private

Definition at line 410 of file ackermann_steering_bot.h.

◆ front_steer_jnt_pos_

double AckermannSteeringBot::front_steer_jnt_pos_
private

Definition at line 412 of file ackermann_steering_bot.h.

◆ front_steer_jnt_pos_cmd_

double AckermannSteeringBot::front_steer_jnt_pos_cmd_
private

Definition at line 416 of file ackermann_steering_bot.h.

◆ front_steer_jnt_pos_cmd_interface_

hardware_interface::PositionJointInterface AckermannSteeringBot::front_steer_jnt_pos_cmd_interface_
private

Definition at line 418 of file ackermann_steering_bot.h.

◆ front_steer_jnt_vel_

double AckermannSteeringBot::front_steer_jnt_vel_
private

Definition at line 413 of file ackermann_steering_bot.h.

◆ jnt_state_interface_

hardware_interface::JointStateInterface AckermannSteeringBot::jnt_state_interface_
private

Definition at line 374 of file ackermann_steering_bot.h.

◆ nh_

ros::NodeHandle AckermannSteeringBot::nh_
private

Definition at line 439 of file ackermann_steering_bot.h.

◆ ns_

std::string AckermannSteeringBot::ns_
private

Definition at line 436 of file ackermann_steering_bot.h.

◆ rear_wheel_jnt_eff_

double AckermannSteeringBot::rear_wheel_jnt_eff_
private

Definition at line 381 of file ackermann_steering_bot.h.

◆ rear_wheel_jnt_name_

std::string AckermannSteeringBot::rear_wheel_jnt_name_
private

Definition at line 377 of file ackermann_steering_bot.h.

◆ rear_wheel_jnt_pos_

double AckermannSteeringBot::rear_wheel_jnt_pos_
private

Definition at line 379 of file ackermann_steering_bot.h.

◆ rear_wheel_jnt_vel_

double AckermannSteeringBot::rear_wheel_jnt_vel_
private

Definition at line 380 of file ackermann_steering_bot.h.

◆ rear_wheel_jnt_vel_cmd_

double AckermannSteeringBot::rear_wheel_jnt_vel_cmd_
private

Definition at line 383 of file ackermann_steering_bot.h.

◆ rear_wheel_jnt_vel_cmd_interface_

hardware_interface::VelocityJointInterface AckermannSteeringBot::rear_wheel_jnt_vel_cmd_interface_
private

Definition at line 385 of file ackermann_steering_bot.h.

◆ running_

bool AckermannSteeringBot::running_
private

Definition at line 437 of file ackermann_steering_bot.h.

◆ start_srv_

ros::ServiceServer AckermannSteeringBot::start_srv_
private

Definition at line 440 of file ackermann_steering_bot.h.

◆ stop_srv_

ros::ServiceServer AckermannSteeringBot::stop_srv_
private

Definition at line 441 of file ackermann_steering_bot.h.

◆ virtual_front_steer_jnt_eff_

std::vector<double> AckermannSteeringBot::virtual_front_steer_jnt_eff_
private

Definition at line 427 of file ackermann_steering_bot.h.

◆ virtual_front_steer_jnt_names_

std::vector<std::string> AckermannSteeringBot::virtual_front_steer_jnt_names_
private

Definition at line 423 of file ackermann_steering_bot.h.

◆ virtual_front_steer_jnt_pos_

std::vector<double> AckermannSteeringBot::virtual_front_steer_jnt_pos_
private

Definition at line 425 of file ackermann_steering_bot.h.

◆ virtual_front_steer_jnt_pos_cmd_

std::vector<double> AckermannSteeringBot::virtual_front_steer_jnt_pos_cmd_
private

Definition at line 429 of file ackermann_steering_bot.h.

◆ virtual_front_steer_jnt_vel_

std::vector<double> AckermannSteeringBot::virtual_front_steer_jnt_vel_
private

Definition at line 426 of file ackermann_steering_bot.h.

◆ virtual_front_wheel_jnt_eff_

std::vector<double> AckermannSteeringBot::virtual_front_wheel_jnt_eff_
private

Definition at line 403 of file ackermann_steering_bot.h.

◆ virtual_front_wheel_jnt_names_

std::vector<std::string> AckermannSteeringBot::virtual_front_wheel_jnt_names_
private

Definition at line 399 of file ackermann_steering_bot.h.

◆ virtual_front_wheel_jnt_pos_

std::vector<double> AckermannSteeringBot::virtual_front_wheel_jnt_pos_
private

Definition at line 401 of file ackermann_steering_bot.h.

◆ virtual_front_wheel_jnt_vel_

std::vector<double> AckermannSteeringBot::virtual_front_wheel_jnt_vel_
private

Definition at line 402 of file ackermann_steering_bot.h.

◆ virtual_front_wheel_jnt_vel_cmd_

std::vector<double> AckermannSteeringBot::virtual_front_wheel_jnt_vel_cmd_
private

Definition at line 405 of file ackermann_steering_bot.h.

◆ virtual_rear_wheel_jnt_eff_

std::vector<double> AckermannSteeringBot::virtual_rear_wheel_jnt_eff_
private

Definition at line 394 of file ackermann_steering_bot.h.

◆ virtual_rear_wheel_jnt_names_

std::vector<std::string> AckermannSteeringBot::virtual_rear_wheel_jnt_names_
private

Definition at line 390 of file ackermann_steering_bot.h.

◆ virtual_rear_wheel_jnt_pos_

std::vector<double> AckermannSteeringBot::virtual_rear_wheel_jnt_pos_
private

Definition at line 392 of file ackermann_steering_bot.h.

◆ virtual_rear_wheel_jnt_vel_

std::vector<double> AckermannSteeringBot::virtual_rear_wheel_jnt_vel_
private

Definition at line 393 of file ackermann_steering_bot.h.

◆ virtual_rear_wheel_jnt_vel_cmd_

std::vector<double> AckermannSteeringBot::virtual_rear_wheel_jnt_vel_cmd_
private

Definition at line 396 of file ackermann_steering_bot.h.

◆ wheel_separation_h_

double AckermannSteeringBot::wheel_separation_h_
private

Definition at line 434 of file ackermann_steering_bot.h.

◆ wheel_separation_w_

double AckermannSteeringBot::wheel_separation_w_
private

Definition at line 432 of file ackermann_steering_bot.h.


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


ackermann_steering_controller
Author(s): Masaru Morita
autogenerated on Fri Feb 3 2023 03:19:04