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

#include <real_robot.h>

Inheritance diagram for RealRobot:
Inheritance graph
[legend]

Classes

struct  Config
 
struct  Wheel
 

Public Member Functions

const ros::Durationget_period ()
 
const ros::Timeget_time ()
 
void read ()
 
 RealRobot (const Config &cfg)
 
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 Attributes

ArduinoComms arduino_
 
hardware_interface::JointStateInterface jnt_state_interface_
 
hardware_interface::VelocityJointInterface jnt_vel_interface_
 
Wheel l_wheel_
 
float loop_rate_
 
ros::Duration period_
 
Wheel r_wheel_
 
ros::Time time_
 

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 11 of file real_robot.h.

Constructor & Destructor Documentation

◆ RealRobot()

RealRobot::RealRobot ( const Config cfg)

Definition at line 17 of file real_robot.cpp.

Member Function Documentation

◆ get_period()

const ros::Duration& RealRobot::get_period ( )
inline

Definition at line 56 of file real_robot.h.

◆ get_time()

const ros::Time& RealRobot::get_time ( )
inline

Definition at line 55 of file real_robot.h.

◆ read()

void RealRobot::read ( )

Definition at line 49 of file real_robot.cpp.

◆ write()

void RealRobot::write ( )

Definition at line 72 of file real_robot.cpp.

Member Data Documentation

◆ arduino_

ArduinoComms RealRobot::arduino_
private

Definition at line 61 of file real_robot.h.

◆ jnt_state_interface_

hardware_interface::JointStateInterface RealRobot::jnt_state_interface_
private

Definition at line 59 of file real_robot.h.

◆ jnt_vel_interface_

hardware_interface::VelocityJointInterface RealRobot::jnt_vel_interface_
private

Definition at line 60 of file real_robot.h.

◆ l_wheel_

Wheel RealRobot::l_wheel_
private

Definition at line 63 of file real_robot.h.

◆ loop_rate_

float RealRobot::loop_rate_
private

Definition at line 68 of file real_robot.h.

◆ period_

ros::Duration RealRobot::period_
private

Definition at line 67 of file real_robot.h.

◆ r_wheel_

Wheel RealRobot::r_wheel_
private

Definition at line 64 of file real_robot.h.

◆ time_

ros::Time RealRobot::time_
private

Definition at line 66 of file real_robot.h.


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


diffdrive_arduino
Author(s): Josh Newans
autogenerated on Mon Feb 28 2022 22:13:39