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

#include <mrp2_hardware.h>

Inheritance diagram for MRP2HW:
Inheritance graph
[legend]

Public Member Functions

void callback (mrp2_hardware::ParametersConfig &config, uint32_t level)
 
void estop_clear_callback (const std_msgs::Empty::ConstPtr &msg)
 
ros::Duration getPeriod () const
 
ros::Time getTime () const
 
 MRP2HW ()
 
void positions_reset_callback (const std_msgs::Empty::ConstPtr &msg)
 
void read ()
 
bool start_callback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 
bool stop_callback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 
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)
 

Public Attributes

bool estop_release
 
- Public Attributes inherited from hardware_interface::RobotHW
 DONE
 
 ERROR
 
 ONGOING
 

Private Member Functions

double _ftod (float fValue)
 

Private Attributes

ros::Publisher aux_lights_pub
 
ros::Publisher batt_high_pub
 
ros::Publisher batt_low_pub
 
std::vector< int > bumper_states
 
ros::Publisher bumpers_pub
 
double cmd_ [2]
 
boost::mutex connect_mutex_
 
ros::Publisher controller_pub
 
ros::Time current_time
 
std::vector< int > diags
 
boost::recursive_mutex dynamic_reconfigure_mutex_
 
double eff_ [2]
 
ros::Publisher estop_btn_pub
 
ros::Subscriber estop_clear_sub
 
ros::Publisher estop_pub
 
bool estop_state
 
dynamic_reconfigure::Server< mrp2_hardware::ParametersConfig >::CallbackType f
 
hardware_interface::ImuSensorInterface imu_sens_interface_
 
mrp2_hardware::ParametersConfig init_config
 
hardware_interface::JointStateInterface jnt_state_interface_
 
hardware_interface::VelocityJointInterface jnt_vel_interface_
 
ros::Time last_time
 
ros::Publisher motor_stall_l_pub
 
ros::Publisher motor_stall_r_pub
 
ros::NodeHandle nh_
 
double pos_ [2]
 
double pos_left
 
ros::Subscriber pos_reset_sub
 
double pos_right
 
bool publish_feed
 
bool publish_pos
 
bool publish_ref
 
MRP2_Serialrobot_serial
 
bool running_
 
ros::Publisher sep_cmd_vel_pub
 
dynamic_reconfigure::Server< mrp2_hardware::ParametersConfig > server
 
std::vector< int > speeds
 
ros::ServiceServer start_srv_
 
ros::ServiceServer stop_srv_
 
bool sym_tuning
 
double vel_ [2]
 

Additional Inherited Members

- Public Types inherited from hardware_interface::RobotHW
enum  SwitchState
 
- 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 36 of file mrp2_hardware.h.

Constructor & Destructor Documentation

◆ MRP2HW()

MRP2HW::MRP2HW ( )
inline

Definition at line 39 of file mrp2_hardware.h.

Member Function Documentation

◆ _ftod()

double MRP2HW::_ftod ( float  fValue)
inlineprivate

Definition at line 355 of file mrp2_hardware.h.

◆ callback()

void MRP2HW::callback ( mrp2_hardware::ParametersConfig &  config,
uint32_t  level 
)
inline

Definition at line 294 of file mrp2_hardware.h.

◆ estop_clear_callback()

void MRP2HW::estop_clear_callback ( const std_msgs::Empty::ConstPtr &  msg)
inline

Definition at line 288 of file mrp2_hardware.h.

◆ getPeriod()

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

Definition at line 136 of file mrp2_hardware.h.

◆ getTime()

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

Definition at line 135 of file mrp2_hardware.h.

◆ positions_reset_callback()

void MRP2HW::positions_reset_callback ( const std_msgs::Empty::ConstPtr &  msg)
inline

Definition at line 282 of file mrp2_hardware.h.

◆ read()

void MRP2HW::read ( )
inline

Definition at line 140 of file mrp2_hardware.h.

◆ start_callback()

bool MRP2HW::start_callback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)
inline

Definition at line 270 of file mrp2_hardware.h.

◆ stop_callback()

bool MRP2HW::stop_callback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)
inline

Definition at line 276 of file mrp2_hardware.h.

◆ write()

void MRP2HW::write ( )
inline

Definition at line 234 of file mrp2_hardware.h.

Member Data Documentation

◆ aux_lights_pub

ros::Publisher MRP2HW::aux_lights_pub
private

Definition at line 339 of file mrp2_hardware.h.

◆ batt_high_pub

ros::Publisher MRP2HW::batt_high_pub
private

Definition at line 337 of file mrp2_hardware.h.

◆ batt_low_pub

ros::Publisher MRP2HW::batt_low_pub
private

Definition at line 336 of file mrp2_hardware.h.

◆ bumper_states

std::vector<int> MRP2HW::bumper_states
private

Definition at line 324 of file mrp2_hardware.h.

◆ bumpers_pub

ros::Publisher MRP2HW::bumpers_pub
private

Definition at line 330 of file mrp2_hardware.h.

◆ cmd_

double MRP2HW::cmd_[2]
private

Definition at line 311 of file mrp2_hardware.h.

◆ connect_mutex_

boost::mutex MRP2HW::connect_mutex_
private

Definition at line 351 of file mrp2_hardware.h.

◆ controller_pub

ros::Publisher MRP2HW::controller_pub
private

Definition at line 338 of file mrp2_hardware.h.

◆ current_time

ros::Time MRP2HW::current_time
private

Definition at line 346 of file mrp2_hardware.h.

◆ diags

std::vector<int> MRP2HW::diags
private

Definition at line 324 of file mrp2_hardware.h.

◆ dynamic_reconfigure_mutex_

boost::recursive_mutex MRP2HW::dynamic_reconfigure_mutex_
private

Definition at line 350 of file mrp2_hardware.h.

◆ eff_

double MRP2HW::eff_[2]
private

Definition at line 314 of file mrp2_hardware.h.

◆ estop_btn_pub

ros::Publisher MRP2HW::estop_btn_pub
private

Definition at line 333 of file mrp2_hardware.h.

◆ estop_clear_sub

ros::Subscriber MRP2HW::estop_clear_sub
private

Definition at line 344 of file mrp2_hardware.h.

◆ estop_pub

ros::Publisher MRP2HW::estop_pub
private

Definition at line 332 of file mrp2_hardware.h.

◆ estop_release

bool MRP2HW::estop_release

Definition at line 138 of file mrp2_hardware.h.

◆ estop_state

bool MRP2HW::estop_state
private

Definition at line 318 of file mrp2_hardware.h.

◆ f

dynamic_reconfigure::Server<mrp2_hardware::ParametersConfig>::CallbackType MRP2HW::f
private

Definition at line 349 of file mrp2_hardware.h.

◆ imu_sens_interface_

hardware_interface::ImuSensorInterface MRP2HW::imu_sens_interface_
private

Definition at line 310 of file mrp2_hardware.h.

◆ init_config

mrp2_hardware::ParametersConfig MRP2HW::init_config
private

Definition at line 353 of file mrp2_hardware.h.

◆ jnt_state_interface_

hardware_interface::JointStateInterface MRP2HW::jnt_state_interface_
private

Definition at line 308 of file mrp2_hardware.h.

◆ jnt_vel_interface_

hardware_interface::VelocityJointInterface MRP2HW::jnt_vel_interface_
private

Definition at line 309 of file mrp2_hardware.h.

◆ last_time

ros::Time MRP2HW::last_time
private

Definition at line 346 of file mrp2_hardware.h.

◆ motor_stall_l_pub

ros::Publisher MRP2HW::motor_stall_l_pub
private

Definition at line 334 of file mrp2_hardware.h.

◆ motor_stall_r_pub

ros::Publisher MRP2HW::motor_stall_r_pub
private

Definition at line 335 of file mrp2_hardware.h.

◆ nh_

ros::NodeHandle MRP2HW::nh_
private

Definition at line 326 of file mrp2_hardware.h.

◆ pos_

double MRP2HW::pos_[2]
private

Definition at line 312 of file mrp2_hardware.h.

◆ pos_left

double MRP2HW::pos_left
private

Definition at line 320 of file mrp2_hardware.h.

◆ pos_reset_sub

ros::Subscriber MRP2HW::pos_reset_sub
private

Definition at line 343 of file mrp2_hardware.h.

◆ pos_right

double MRP2HW::pos_right
private

Definition at line 320 of file mrp2_hardware.h.

◆ publish_feed

bool MRP2HW::publish_feed
private

Definition at line 317 of file mrp2_hardware.h.

◆ publish_pos

bool MRP2HW::publish_pos
private

Definition at line 317 of file mrp2_hardware.h.

◆ publish_ref

bool MRP2HW::publish_ref
private

Definition at line 317 of file mrp2_hardware.h.

◆ robot_serial

MRP2_Serial* MRP2HW::robot_serial
private

Definition at line 323 of file mrp2_hardware.h.

◆ running_

bool MRP2HW::running_
private

Definition at line 315 of file mrp2_hardware.h.

◆ sep_cmd_vel_pub

ros::Publisher MRP2HW::sep_cmd_vel_pub
private

Definition at line 341 of file mrp2_hardware.h.

◆ server

dynamic_reconfigure::Server<mrp2_hardware::ParametersConfig> MRP2HW::server
private

Definition at line 348 of file mrp2_hardware.h.

◆ speeds

std::vector<int> MRP2HW::speeds
private

Definition at line 324 of file mrp2_hardware.h.

◆ start_srv_

ros::ServiceServer MRP2HW::start_srv_
private

Definition at line 327 of file mrp2_hardware.h.

◆ stop_srv_

ros::ServiceServer MRP2HW::stop_srv_
private

Definition at line 328 of file mrp2_hardware.h.

◆ sym_tuning

bool MRP2HW::sym_tuning
private

Definition at line 317 of file mrp2_hardware.h.

◆ vel_

double MRP2HW::vel_[2]
private

Definition at line 313 of file mrp2_hardware.h.


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


mrp2_hardware
Author(s): Akif Hacinecipoglu
autogenerated on Mon Feb 28 2022 22:53:03