Public Member Functions | Private Types | Private Member Functions | Private Attributes
steer_bot_hardware_gazebo::SteerBotHardwareGazebo Class Reference

#include <steer_bot_hardware_gazebo.h>

Inheritance diagram for steer_bot_hardware_gazebo::SteerBotHardwareGazebo:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool initSim (const std::string &robot_namespace, ros::NodeHandle model_nh, gazebo::physics::ModelPtr parent_model, const urdf::Model *const urdf_model, std::vector< transmission_interface::TransmissionInfo > transmissions)
void readSim (ros::Time time, ros::Duration period)
 SteerBotHardwareGazebo ()
void writeSim (ros::Time time, ros::Duration period)

Private Types

enum  { INDEX_RIGHT = 0, INDEX_LEFT = 1 }

Private Member Functions

void CleanUp ()
double ComputeEffCommandFromVelError (const int _index, ros::Duration _period)
template<class T >
std::string containerToString (const T &cont, const std::string &prefix)
void GetCurrentState (std::vector< double > &_jnt_pos, std::vector< double > &_jnt_vel, std::vector< double > &_jnt_eff, const int _if_index, const int _sim_jnt_index)
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

bool enable_ackermann_link_
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::VelocityJointInterface front_wheel_jnt_vel_cmd_interface_
joint_limits_interface::PositionJointSoftLimitsInterface jnt_limits_interface_
hardware_interface::JointStateInterface jnt_state_interface_
int log_cnt_
unsigned int n_dof_
ros::NodeHandle nh_
std::string ns_
std::vector< control_toolbox::Pidpids_
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_
std::vector
< gazebo::physics::JointPtr > 
sim_joints_
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 66 of file steer_bot_hardware_gazebo.h.


Member Enumeration Documentation

anonymous enum [private]
Enumerator:
INDEX_RIGHT 
INDEX_LEFT 

Definition at line 110 of file steer_bot_hardware_gazebo.h.


Constructor & Destructor Documentation

Definition at line 54 of file steer_bot_hardware_gazebo.cpp.


Member Function Documentation

Definition at line 277 of file steer_bot_hardware_gazebo.cpp.

Definition at line 447 of file steer_bot_hardware_gazebo.cpp.

template<class T >
std::string steer_bot_hardware_gazebo::SteerBotHardwareGazebo::containerToString ( const T cont,
const std::string &  prefix 
) [inline, private]

Definition at line 198 of file steer_bot_hardware_gazebo.h.

void steer_bot_hardware_gazebo::SteerBotHardwareGazebo::GetCurrentState ( std::vector< double > &  _jnt_pos,
std::vector< double > &  _jnt_vel,
std::vector< double > &  _jnt_eff,
const int  _if_index,
const int  _sim_jnt_index 
) [private]

Definition at line 468 of file steer_bot_hardware_gazebo.cpp.

Definition at line 315 of file steer_bot_hardware_gazebo.cpp.

Definition at line 343 of file steer_bot_hardware_gazebo.cpp.

Definition at line 321 of file steer_bot_hardware_gazebo.cpp.

bool steer_bot_hardware_gazebo::SteerBotHardwareGazebo::initSim ( const std::string &  robot_namespace,
ros::NodeHandle  model_nh,
gazebo::physics::ModelPtr  parent_model,
const urdf::Model *const  urdf_model,
std::vector< transmission_interface::TransmissionInfo transmissions 
) [virtual]

Implements gazebo_ros_control::RobotHWSim.

Definition at line 61 of file steer_bot_hardware_gazebo.cpp.

Implements gazebo_ros_control::RobotHWSim.

Definition at line 137 of file steer_bot_hardware_gazebo.cpp.

void steer_bot_hardware_gazebo::SteerBotHardwareGazebo::RegisterCommandJointInterfaceHandle ( hardware_interface::JointStateInterface _jnt_state_interface,
hardware_interface::JointCommandInterface _jnt_cmd_interface,
const std::string  _jnt_name,
double &  _jnt_cmd 
) [private]

Definition at line 433 of file steer_bot_hardware_gazebo.cpp.

Definition at line 358 of file steer_bot_hardware_gazebo.cpp.

void steer_bot_hardware_gazebo::SteerBotHardwareGazebo::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 
) [private]

Definition at line 369 of file steer_bot_hardware_gazebo.cpp.

void steer_bot_hardware_gazebo::SteerBotHardwareGazebo::RegisterJointStateInterfaceHandle ( hardware_interface::JointStateInterface _jnt_state_interface,
const std::string  _jnt_name,
double &  _jnt_pos,
double &  _jnt_vel,
double &  _jnt_eff 
) [private]

Definition at line 420 of file steer_bot_hardware_gazebo.cpp.

Definition at line 404 of file steer_bot_hardware_gazebo.cpp.

Definition at line 381 of file steer_bot_hardware_gazebo.cpp.

Implements gazebo_ros_control::RobotHWSim.

Definition at line 179 of file steer_bot_hardware_gazebo.cpp.


Member Data Documentation

Definition at line 191 of file steer_bot_hardware_gazebo.h.

Definition at line 171 of file steer_bot_hardware_gazebo.h.

Definition at line 167 of file steer_bot_hardware_gazebo.h.

Definition at line 169 of file steer_bot_hardware_gazebo.h.

Definition at line 173 of file steer_bot_hardware_gazebo.h.

Definition at line 175 of file steer_bot_hardware_gazebo.h.

Definition at line 170 of file steer_bot_hardware_gazebo.h.

Definition at line 188 of file steer_bot_hardware_gazebo.h.

Definition at line 119 of file steer_bot_hardware_gazebo.h.

Definition at line 129 of file steer_bot_hardware_gazebo.h.

Definition at line 195 of file steer_bot_hardware_gazebo.h.

Definition at line 115 of file steer_bot_hardware_gazebo.h.

Definition at line 125 of file steer_bot_hardware_gazebo.h.

Definition at line 126 of file steer_bot_hardware_gazebo.h.

Definition at line 122 of file steer_bot_hardware_gazebo.h.

Definition at line 138 of file steer_bot_hardware_gazebo.h.

Definition at line 134 of file steer_bot_hardware_gazebo.h.

Definition at line 136 of file steer_bot_hardware_gazebo.h.

Definition at line 137 of file steer_bot_hardware_gazebo.h.

Definition at line 140 of file steer_bot_hardware_gazebo.h.

Definition at line 142 of file steer_bot_hardware_gazebo.h.

std::vector<gazebo::physics::JointPtr> steer_bot_hardware_gazebo::SteerBotHardwareGazebo::sim_joints_ [private]

Definition at line 116 of file steer_bot_hardware_gazebo.h.

Definition at line 184 of file steer_bot_hardware_gazebo.h.

Definition at line 180 of file steer_bot_hardware_gazebo.h.

Definition at line 182 of file steer_bot_hardware_gazebo.h.

Definition at line 186 of file steer_bot_hardware_gazebo.h.

Definition at line 183 of file steer_bot_hardware_gazebo.h.

Definition at line 160 of file steer_bot_hardware_gazebo.h.

Definition at line 156 of file steer_bot_hardware_gazebo.h.

Definition at line 158 of file steer_bot_hardware_gazebo.h.

Definition at line 159 of file steer_bot_hardware_gazebo.h.

Definition at line 162 of file steer_bot_hardware_gazebo.h.

Definition at line 151 of file steer_bot_hardware_gazebo.h.

Definition at line 147 of file steer_bot_hardware_gazebo.h.

Definition at line 149 of file steer_bot_hardware_gazebo.h.

Definition at line 150 of file steer_bot_hardware_gazebo.h.

Definition at line 153 of file steer_bot_hardware_gazebo.h.

Definition at line 193 of file steer_bot_hardware_gazebo.h.

Definition at line 192 of file steer_bot_hardware_gazebo.h.


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


steer_bot_hardware_gazebo
Author(s): Enrique Fernandez
autogenerated on Sat Jun 8 2019 19:20:22