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

#include <controller.h>

Inheritance diagram for ROSController:
Inheritance graph
[legend]

Public Member Functions

virtual bool consume (RTState_V1_6__7 &state)
 
virtual bool consume (RTState_V1_8 &state)
 
virtual bool consume (RTState_V3_0__1 &state)
 
virtual bool consume (RTState_V3_2__3 &state)
 
void doSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
 
virtual void onRobotStateChange (RobotState state)
 
virtual void onTimeout ()
 
 ROSController (URCommander &commander, TrajectoryFollower &follower, std::vector< std::string > &joint_names, double max_vel_change, std::string wrench_frame)
 
virtual void setupConsumer ()
 
virtual ~ROSController ()
 
- Public Member Functions inherited from URRTPacketConsumer
virtual bool consume (shared_ptr< RTPacket > packet)
 
- Public Member Functions inherited from IConsumer< RTPacket >
virtual void stopConsumer ()
 
virtual void teardownConsumer ()
 

Private Member Functions

void read (RTShared &state)
 
template<typename T >
void registerControllereInterface (T *interface)
 
template<typename T >
void registerInterface (T *interface)
 
void reset ()
 
bool update ()
 
bool write ()
 
- Private 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 bool init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
virtual void read (const ros::Time &time, const ros::Duration &period)
 
virtual void read (const ros::Time &time, const ros::Duration &period)
 
 RobotHW ()
 
virtual void write (const ros::Time &time, const ros::Duration &period)
 
virtual void write (const ros::Time &time, const ros::Duration &period)
 
virtual ~RobotHW ()
 
- Private 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

HardwareInterfaceactive_interface_
 
std::map< std::string, HardwareInterface * > available_interfaces_
 
controller_manager::ControllerManager controller_
 
JointInterface joint_interface_
 
ros::Time lastUpdate_
 
ros::NodeHandle nh_
 
PositionInterface position_interface_
 
bool robot_state_received_
 
std::atomic< uint32_t > service_cooldown_
 
std::atomic< bool > service_enabled_
 
VelocityInterface velocity_interface_
 
WrenchInterface wrench_interface_
 
- Private Attributes inherited from hardware_interface::InterfaceManager
boost::ptr_vector< ResourceManagerBaseinterface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

Detailed Description

Definition at line 34 of file controller.h.

Constructor & Destructor Documentation

ROSController::ROSController ( URCommander commander,
TrajectoryFollower follower,
std::vector< std::string > &  joint_names,
double  max_vel_change,
std::string  wrench_frame 
)

Definition at line 21 of file controller.cpp.

virtual ROSController::~ROSController ( )
inlinevirtual

Definition at line 78 of file controller.h.

Member Function Documentation

virtual bool ROSController::consume ( RTState_V1_6__7 state)
inlinevirtual

Implements URRTPacketConsumer.

Definition at line 86 of file controller.h.

virtual bool ROSController::consume ( RTState_V1_8 state)
inlinevirtual

Implements URRTPacketConsumer.

Definition at line 91 of file controller.h.

virtual bool ROSController::consume ( RTState_V3_0__1 state)
inlinevirtual

Implements URRTPacketConsumer.

Definition at line 96 of file controller.h.

virtual bool ROSController::consume ( RTState_V3_2__3 state)
inlinevirtual

Implements URRTPacketConsumer.

Definition at line 101 of file controller.h.

void ROSController::doSwitch ( const std::list< hardware_interface::ControllerInfo > &  start_list,
const std::list< hardware_interface::ControllerInfo > &  stop_list 
)
virtual

Reimplemented from hardware_interface::RobotHW.

Definition at line 41 of file controller.cpp.

void ROSController::onRobotStateChange ( RobotState  state)
virtual

Implements Service.

Definition at line 141 of file controller.cpp.

void ROSController::onTimeout ( )
virtual

Reimplemented from IConsumer< RTPacket >.

Definition at line 136 of file controller.cpp.

void ROSController::read ( RTShared state)
private

Definition at line 99 of file controller.cpp.

template<typename T >
void ROSController::registerControllereInterface ( T *  interface)
inlineprivate

Definition at line 64 of file controller.h.

template<typename T >
void ROSController::registerInterface ( T *  interface)
inlineprivate

Definition at line 59 of file controller.h.

void ROSController::reset ( )
private

Definition at line 91 of file controller.cpp.

void ROSController::setupConsumer ( )
virtual

Reimplemented from IConsumer< RTPacket >.

Definition at line 36 of file controller.cpp.

bool ROSController::update ( )
private

Definition at line 106 of file controller.cpp.

bool ROSController::write ( )
private

Definition at line 83 of file controller.cpp.

Member Data Documentation

HardwareInterface* ROSController::active_interface_
private

Definition at line 50 of file controller.h.

std::map<std::string, HardwareInterface*> ROSController::available_interfaces_
private

Definition at line 52 of file controller.h.

controller_manager::ControllerManager ROSController::controller_
private

Definition at line 39 of file controller.h.

JointInterface ROSController::joint_interface_
private

Definition at line 43 of file controller.h.

ros::Time ROSController::lastUpdate_
private

Definition at line 38 of file controller.h.

ros::NodeHandle ROSController::nh_
private

Definition at line 37 of file controller.h.

PositionInterface ROSController::position_interface_
private

Definition at line 46 of file controller.h.

bool ROSController::robot_state_received_
private

Definition at line 40 of file controller.h.

std::atomic<uint32_t> ROSController::service_cooldown_
private

Definition at line 55 of file controller.h.

std::atomic<bool> ROSController::service_enabled_
private

Definition at line 54 of file controller.h.

VelocityInterface ROSController::velocity_interface_
private

Definition at line 47 of file controller.h.

WrenchInterface ROSController::wrench_interface_
private

Definition at line 44 of file controller.h.


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


ur_modern_driver
Author(s): Thomas Timm Andersen, Simon Rasmussen
autogenerated on Fri Jun 26 2020 03:37:01