Public Member Functions | Private Member Functions | Private Attributes
Steerbot Class Reference

#include <steerbot.h>

Inheritance diagram for Steerbot:
Inheritance graph
[legend]

List of all members.

Public Member Functions

ros::Duration getPeriod () const
ros::Time getTime () const
void read ()
bool startCallback (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
 Steerbot ()
bool stopCallback (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
void write ()

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_

Detailed Description

Definition at line 53 of file steerbot.h.


Constructor & Destructor Documentation

Steerbot::Steerbot ( ) [inline]

Definition at line 56 of file steerbot.h.


Member Function Documentation

void Steerbot::cleanUp ( ) [inline, private]

Definition at line 196 of file steerbot.h.

void Steerbot::getJointNames ( ros::NodeHandle _nh) [inline, private]

Definition at line 234 of file steerbot.h.

ros::Duration Steerbot::getPeriod ( ) const [inline]

Definition at line 74 of file steerbot.h.

void Steerbot::getSteerJointNames ( ros::NodeHandle _nh) [inline, private]

Definition at line 261 of file steerbot.h.

ros::Time Steerbot::getTime ( ) const [inline]

Definition at line 73 of file steerbot.h.

void Steerbot::getWheelJointNames ( ros::NodeHandle _nh) [inline, private]

Definition at line 240 of file steerbot.h.

void Steerbot::read ( ) [inline]

Definition at line 76 of file steerbot.h.

void Steerbot::registerCommandJointInterfaceHandle ( hardware_interface::JointStateInterface _jnt_state_interface,
hardware_interface::JointCommandInterface _jnt_cmd_interface,
const std::string  _jnt_name,
double &  _jnt_cmd 
) [inline, private]

Definition at line 351 of file steerbot.h.

void Steerbot::registerHardwareInterfaces ( ) [inline, private]

Definition at line 276 of file steerbot.h.

void Steerbot::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 
) [inline, private]

Definition at line 326 of file steerbot.h.

void Steerbot::registerJointStateInterfaceHandle ( hardware_interface::JointStateInterface _jnt_state_interface,
const std::string  _jnt_name,
double &  _jnt_pos,
double &  _jnt_vel,
double &  _jnt_eff 
) [inline, private]

Definition at line 338 of file steerbot.h.

void Steerbot::registerSteerInterface ( ) [inline, private]

Definition at line 310 of file steerbot.h.

void Steerbot::registerWheelInterface ( ) [inline, private]

Definition at line 287 of file steerbot.h.

bool Steerbot::startCallback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
) [inline]

Definition at line 180 of file steerbot.h.

bool Steerbot::stopCallback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
) [inline]

Definition at line 187 of file steerbot.h.

void Steerbot::write ( ) [inline]

Definition at line 107 of file steerbot.h.


Member Data Documentation

Definition at line 406 of file steerbot.h.

std::string Steerbot::front_steer_jnt_name_ [private]

Definition at line 402 of file steerbot.h.

Definition at line 404 of file steerbot.h.

Definition at line 408 of file steerbot.h.

Definition at line 410 of file steerbot.h.

Definition at line 405 of file steerbot.h.

Definition at line 366 of file steerbot.h.

Definition at line 431 of file steerbot.h.

std::string Steerbot::ns_ [private]

Definition at line 428 of file steerbot.h.

Definition at line 373 of file steerbot.h.

std::string Steerbot::rear_wheel_jnt_name_ [private]

Definition at line 369 of file steerbot.h.

Definition at line 371 of file steerbot.h.

Definition at line 372 of file steerbot.h.

Definition at line 375 of file steerbot.h.

Definition at line 377 of file steerbot.h.

bool Steerbot::running_ [private]

Definition at line 429 of file steerbot.h.

Definition at line 432 of file steerbot.h.

Definition at line 433 of file steerbot.h.

std::vector<double> Steerbot::virtual_front_steer_jnt_eff_ [private]

Definition at line 419 of file steerbot.h.

std::vector<std::string> Steerbot::virtual_front_steer_jnt_names_ [private]

Definition at line 415 of file steerbot.h.

std::vector<double> Steerbot::virtual_front_steer_jnt_pos_ [private]

Definition at line 417 of file steerbot.h.

std::vector<double> Steerbot::virtual_front_steer_jnt_pos_cmd_ [private]

Definition at line 421 of file steerbot.h.

std::vector<double> Steerbot::virtual_front_steer_jnt_vel_ [private]

Definition at line 418 of file steerbot.h.

std::vector<double> Steerbot::virtual_front_wheel_jnt_eff_ [private]

Definition at line 395 of file steerbot.h.

std::vector<std::string> Steerbot::virtual_front_wheel_jnt_names_ [private]

Definition at line 391 of file steerbot.h.

std::vector<double> Steerbot::virtual_front_wheel_jnt_pos_ [private]

Definition at line 393 of file steerbot.h.

std::vector<double> Steerbot::virtual_front_wheel_jnt_vel_ [private]

Definition at line 394 of file steerbot.h.

std::vector<double> Steerbot::virtual_front_wheel_jnt_vel_cmd_ [private]

Definition at line 397 of file steerbot.h.

std::vector<double> Steerbot::virtual_rear_wheel_jnt_eff_ [private]

Definition at line 386 of file steerbot.h.

std::vector<std::string> Steerbot::virtual_rear_wheel_jnt_names_ [private]

Definition at line 382 of file steerbot.h.

std::vector<double> Steerbot::virtual_rear_wheel_jnt_pos_ [private]

Definition at line 384 of file steerbot.h.

std::vector<double> Steerbot::virtual_rear_wheel_jnt_vel_ [private]

Definition at line 385 of file steerbot.h.

std::vector<double> Steerbot::virtual_rear_wheel_jnt_vel_cmd_ [private]

Definition at line 388 of file steerbot.h.

Definition at line 426 of file steerbot.h.

Definition at line 424 of file steerbot.h.


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


steer_drive_controller
Author(s): CIR-KIT , Masaru Morita
autogenerated on Sat Jun 8 2019 19:20:25