#include <controller.h>
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 | |
HardwareInterface * | active_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< ResourceManagerBase > | interface_destruction_list_ |
InterfaceManagerVector | interface_managers_ |
InterfaceMap | interfaces_ |
InterfaceMap | interfaces_combo_ |
SizeMap | num_ifaces_registered_ |
ResourceMap | resources_ |
Definition at line 34 of file controller.h.
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.
|
inlinevirtual |
Definition at line 78 of file controller.h.
|
inlinevirtual |
Implements URRTPacketConsumer.
Definition at line 86 of file controller.h.
|
inlinevirtual |
Implements URRTPacketConsumer.
Definition at line 91 of file controller.h.
|
inlinevirtual |
Implements URRTPacketConsumer.
Definition at line 96 of file controller.h.
|
inlinevirtual |
Implements URRTPacketConsumer.
Definition at line 101 of file controller.h.
|
virtual |
Reimplemented from hardware_interface::RobotHW.
Definition at line 41 of file controller.cpp.
|
virtual |
Implements Service.
Definition at line 141 of file controller.cpp.
|
virtual |
Reimplemented from IConsumer< RTPacket >.
Definition at line 136 of file controller.cpp.
|
private |
Definition at line 99 of file controller.cpp.
|
inlineprivate |
Definition at line 64 of file controller.h.
|
inlineprivate |
Definition at line 59 of file controller.h.
|
private |
Definition at line 91 of file controller.cpp.
|
virtual |
Reimplemented from IConsumer< RTPacket >.
Definition at line 36 of file controller.cpp.
|
private |
Definition at line 106 of file controller.cpp.
|
private |
Definition at line 83 of file controller.cpp.
|
private |
Definition at line 50 of file controller.h.
|
private |
Definition at line 52 of file controller.h.
|
private |
Definition at line 39 of file controller.h.
|
private |
Definition at line 43 of file controller.h.
|
private |
Definition at line 38 of file controller.h.
|
private |
Definition at line 37 of file controller.h.
|
private |
Definition at line 46 of file controller.h.
|
private |
Definition at line 40 of file controller.h.
|
private |
Definition at line 55 of file controller.h.
|
private |
Definition at line 54 of file controller.h.
|
private |
Definition at line 47 of file controller.h.
|
private |
Definition at line 44 of file controller.h.