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

#include <robot_layer.h>

Inheritance diagram for RobotLayer:
Inheritance graph
[legend]

List of all members.

Classes

struct  SwitchData

Public Member Functions

void add (const std::string &name, boost::shared_ptr< HandleLayer > 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)
boost::shared_ptr< const
urdf::Joint > 
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< HandleLayer > > 
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 218 of file robot_layer.h.


Member Typedef Documentation

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

Definition at line 234 of file robot_layer.h.

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

Definition at line 241 of file robot_layer.h.

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

Definition at line 242 of file robot_layer.h.


Constructor & Destructor Documentation

Definition at line 307 of file robot_layer.cpp.


Member Function Documentation

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

Definition at line 302 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 452 of file robot_layer.cpp.

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

Definition at line 353 of file robot_layer.cpp.

boost::shared_ptr<const urdf::Joint> RobotLayer::getJoint ( const std::string &  n) const [inline]

Definition at line 251 of file robot_layer.h.

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

Reimplemented from canopen::LayerGroup< T >.

Definition at line 317 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 359 of file robot_layer.cpp.

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

Definition at line 294 of file robot_layer.cpp.


Member Data Documentation

Definition at line 222 of file robot_layer.h.

Definition at line 229 of file robot_layer.h.

Definition at line 228 of file robot_layer.h.

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

Definition at line 245 of file robot_layer.h.

Definition at line 235 of file robot_layer.h.

Definition at line 231 of file robot_layer.h.

Definition at line 220 of file robot_layer.h.

Definition at line 225 of file robot_layer.h.

Definition at line 224 of file robot_layer.h.

Definition at line 219 of file robot_layer.h.

Definition at line 243 of file robot_layer.h.

Definition at line 232 of file robot_layer.h.

Definition at line 221 of file robot_layer.h.

Definition at line 227 of file robot_layer.h.

Definition at line 226 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 Thu Jun 6 2019 20:44:07