Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes
canopen::RobotLayer Class Reference

#include <robot_layer.h>

Inheritance diagram for canopen::RobotLayer:
Inheritance graph
[legend]

List of all members.

Classes

struct  SwitchData

Public Member Functions

void add (const std::string &name, boost::shared_ptr< HandleLayerBase > handle)
virtual void doSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
void enforce (const ros::Duration &period, bool reset)
urdf::JointConstSharedPtr getJoint (const std::string &n) const
virtual void handleInit (canopen::LayerStatus &status)
virtual bool prepareSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
 RobotLayer (ros::NodeHandle nh)

Private Types

typedef boost::unordered_map
< std::string,
boost::shared_ptr
< HandleLayerBase > > 
HandleMap
typedef std::vector< SwitchDataSwitchContainer
typedef boost::unordered_map
< std::string, SwitchContainer
SwitchMap

Private Member Functions

void stopControllers (const std::vector< std::string > controllers)

Private Attributes

hardware_interface::EffortJointInterface eff_interface_
joint_limits_interface::EffortJointSaturationInterface eff_saturation_interface_
joint_limits_interface::EffortJointSoftLimitsInterface eff_soft_limits_interface_
boost::atomic< bool > first_init_
HandleMap handles_
ros::NodeHandle nh_
hardware_interface::PositionJointInterface pos_interface_
joint_limits_interface::PositionJointSaturationInterface pos_saturation_interface_
joint_limits_interface::PositionJointSoftLimitsInterface pos_soft_limits_interface_
hardware_interface::JointStateInterface state_interface_
SwitchMap switch_map_
urdf::Model urdf_
hardware_interface::VelocityJointInterface vel_interface_
joint_limits_interface::VelocityJointSaturationInterface vel_saturation_interface_
joint_limits_interface::VelocityJointSoftLimitsInterface vel_soft_limits_interface_

Detailed Description

Definition at line 18 of file robot_layer.h.


Member Typedef Documentation

typedef boost::unordered_map< std::string, boost::shared_ptr<HandleLayerBase> > canopen::RobotLayer::HandleMap [private]

Definition at line 34 of file robot_layer.h.

typedef std::vector<SwitchData> canopen::RobotLayer::SwitchContainer [private]

Definition at line 41 of file robot_layer.h.

typedef boost::unordered_map<std::string, SwitchContainer> canopen::RobotLayer::SwitchMap [private]

Definition at line 42 of file robot_layer.h.


Constructor & Destructor Documentation

Definition at line 31 of file robot_layer.cpp.


Member Function Documentation

void RobotLayer::add ( const std::string &  name,
boost::shared_ptr< HandleLayerBase handle 
)

Definition at line 26 of file robot_layer.cpp.

void RobotLayer::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 222 of file robot_layer.cpp.

void RobotLayer::enforce ( const ros::Duration period,
bool  reset 
)

Definition at line 77 of file robot_layer.cpp.

urdf::JointConstSharedPtr canopen::RobotLayer::getJoint ( const std::string &  n) const [inline]

Definition at line 51 of file robot_layer.h.

void RobotLayer::handleInit ( canopen::LayerStatus status) [virtual]

Reimplemented from canopen::LayerGroup< T >.

Definition at line 41 of file robot_layer.cpp.

bool RobotLayer::prepareSwitch ( 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 106 of file robot_layer.cpp.

void RobotLayer::stopControllers ( const std::vector< std::string >  controllers) [private]

Definition at line 18 of file robot_layer.cpp.


Member Data Documentation

Definition at line 22 of file robot_layer.h.

Definition at line 29 of file robot_layer.h.

Definition at line 28 of file robot_layer.h.

boost::atomic<bool> canopen::RobotLayer::first_init_ [private]

Definition at line 45 of file robot_layer.h.

Definition at line 35 of file robot_layer.h.

Definition at line 31 of file robot_layer.h.

Definition at line 20 of file robot_layer.h.

Definition at line 25 of file robot_layer.h.

Definition at line 24 of file robot_layer.h.

Definition at line 19 of file robot_layer.h.

Definition at line 43 of file robot_layer.h.

Definition at line 32 of file robot_layer.h.

Definition at line 21 of file robot_layer.h.

Definition at line 27 of file robot_layer.h.

Definition at line 26 of file robot_layer.h.


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


canopen_motor_node
Author(s): Mathias Lüdtke
autogenerated on Sun Sep 3 2017 03:10:55