#include <robot_layer.h>
Definition at line 18 of file robot_layer.h.
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.
Definition at line 31 of file robot_layer.cpp.
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.
Definition at line 22 of file robot_layer.h.
joint_limits_interface::EffortJointSaturationInterface canopen::RobotLayer::eff_saturation_interface_ [private] |
Definition at line 29 of file robot_layer.h.
joint_limits_interface::EffortJointSoftLimitsInterface canopen::RobotLayer::eff_soft_limits_interface_ [private] |
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.
HandleMap canopen::RobotLayer::handles_ [private] |
Definition at line 35 of file robot_layer.h.
ros::NodeHandle canopen::RobotLayer::nh_ [private] |
Definition at line 31 of file robot_layer.h.
Definition at line 20 of file robot_layer.h.
joint_limits_interface::PositionJointSaturationInterface canopen::RobotLayer::pos_saturation_interface_ [private] |
Definition at line 25 of file robot_layer.h.
joint_limits_interface::PositionJointSoftLimitsInterface canopen::RobotLayer::pos_soft_limits_interface_ [private] |
Definition at line 24 of file robot_layer.h.
Definition at line 19 of file robot_layer.h.
SwitchMap canopen::RobotLayer::switch_map_ [private] |
Definition at line 43 of file robot_layer.h.
urdf::Model canopen::RobotLayer::urdf_ [private] |
Definition at line 32 of file robot_layer.h.
Definition at line 21 of file robot_layer.h.
joint_limits_interface::VelocityJointSaturationInterface canopen::RobotLayer::vel_saturation_interface_ [private] |
Definition at line 27 of file robot_layer.h.
joint_limits_interface::VelocityJointSoftLimitsInterface canopen::RobotLayer::vel_soft_limits_interface_ [private] |
Definition at line 26 of file robot_layer.h.