#include <handle_layer.h>
Definition at line 84 of file handle_layer.h.
typedef boost::unordered_map< MotorBase::OperationMode,hardware_interface::JointHandle* > canopen::HandleLayer::CommandMap [private] |
Definition at line 102 of file handle_layer.h.
HandleLayer::HandleLayer | ( | const std::string & | name, |
const boost::shared_ptr< canopen::MotorBase > & | motor, | ||
const boost::shared_ptr< canopen::ObjectStorage > | storage, | ||
XmlRpc::XmlRpcValue & | options | ||
) |
Definition at line 26 of file handle_layer.cpp.
hardware_interface::JointHandle* canopen::HandleLayer::addHandle | ( | T & | iface, |
hardware_interface::JointHandle * | jh, | ||
const std::vector< MotorBase::OperationMode > & | modes | ||
) | [inline, private] |
Definition at line 105 of file handle_layer.h.
static double* canopen::HandleLayer::assignVariable | ( | const std::string & | name, |
double * | ptr, | ||
const std::string & | req | ||
) | [inline, static] |
Definition at line 129 of file handle_layer.h.
HandleLayer::CanSwitchResult HandleLayer::canSwitch | ( | const canopen::MotorBase::OperationMode & | m | ) | [virtual] |
Implements canopen::HandleLayerBase.
Definition at line 59 of file handle_layer.cpp.
void HandleLayer::enableLimits | ( | bool | enable | ) | [virtual] |
Implements canopen::HandleLayerBase.
Definition at line 212 of file handle_layer.cpp.
void HandleLayer::enforceLimits | ( | const ros::Duration & | period, |
bool | reset | ||
) | [virtual] |
Implements canopen::HandleLayerBase.
Definition at line 205 of file handle_layer.cpp.
bool HandleLayer::forwardForMode | ( | const canopen::MotorBase::OperationMode & | m | ) | [virtual] |
Implements canopen::HandleLayerBase.
Definition at line 85 of file handle_layer.cpp.
virtual void canopen::HandleLayer::handleDiag | ( | canopen::LayerReport & | report | ) | [inline, private, virtual] |
Implements canopen::Layer.
Definition at line 157 of file handle_layer.h.
virtual void canopen::HandleLayer::handleHalt | ( | canopen::LayerStatus & | status | ) | [inline, private, virtual] |
Implements canopen::Layer.
Definition at line 159 of file handle_layer.h.
void HandleLayer::handleInit | ( | canopen::LayerStatus & | status | ) | [private, virtual] |
Implements canopen::Layer.
Definition at line 189 of file handle_layer.cpp.
void HandleLayer::handleRead | ( | canopen::LayerStatus & | status, |
const LayerState & | current_state | ||
) | [private, virtual] |
Implements canopen::Layer.
Definition at line 137 of file handle_layer.cpp.
virtual void canopen::HandleLayer::handleRecover | ( | canopen::LayerStatus & | status | ) | [inline, private, virtual] |
Implements canopen::Layer.
Definition at line 160 of file handle_layer.h.
virtual void canopen::HandleLayer::handleShutdown | ( | canopen::LayerStatus & | status | ) | [inline, private, virtual] |
Implements canopen::Layer.
Definition at line 158 of file handle_layer.h.
void HandleLayer::handleWrite | ( | canopen::LayerStatus & | status, |
const LayerState & | current_state | ||
) | [private, virtual] |
Implements canopen::Layer.
Definition at line 145 of file handle_layer.cpp.
bool HandleLayer::prepareFilters | ( | canopen::LayerStatus & | status | ) |
Definition at line 183 of file handle_layer.cpp.
void canopen::HandleLayer::registerHandle | ( | hardware_interface::JointStateInterface & | iface | ) | [inline, virtual] |
Implements canopen::HandleLayerBase.
Definition at line 135 of file handle_layer.h.
hardware_interface::JointHandle * HandleLayer::registerHandle | ( | hardware_interface::PositionJointInterface & | iface, |
const joint_limits_interface::JointLimits & | limits, | ||
const joint_limits_interface::SoftJointLimits * | soft_limits = 0 |
||
) | [virtual] |
Implements canopen::HandleLayerBase.
Definition at line 98 of file handle_layer.cpp.
hardware_interface::JointHandle * HandleLayer::registerHandle | ( | hardware_interface::VelocityJointInterface & | iface, |
const joint_limits_interface::JointLimits & | limits, | ||
const joint_limits_interface::SoftJointLimits * | soft_limits = 0 |
||
) | [virtual] |
Implements canopen::HandleLayerBase.
Definition at line 111 of file handle_layer.cpp.
hardware_interface::JointHandle * HandleLayer::registerHandle | ( | hardware_interface::EffortJointInterface & | iface, |
const joint_limits_interface::JointLimits & | limits, | ||
const joint_limits_interface::SoftJointLimits * | soft_limits = 0 |
||
) | [virtual] |
Implements canopen::HandleLayerBase.
Definition at line 124 of file handle_layer.cpp.
bool HandleLayer::select | ( | const canopen::MotorBase::OperationMode & | m | ) | [private] |
Definition at line 19 of file handle_layer.cpp.
bool HandleLayer::switchMode | ( | const canopen::MotorBase::OperationMode & | m | ) | [virtual] |
Implements canopen::HandleLayerBase.
Definition at line 71 of file handle_layer.cpp.
double canopen::HandleLayer::cmd_eff_ [private] |
Definition at line 88 of file handle_layer.h.
double canopen::HandleLayer::cmd_pos_ [private] |
Definition at line 88 of file handle_layer.h.
double canopen::HandleLayer::cmd_vel_ [private] |
Definition at line 88 of file handle_layer.h.
CommandMap canopen::HandleLayer::commands_ [private] |
Definition at line 103 of file handle_layer.h.
boost::scoped_ptr<UnitConverter> canopen::HandleLayer::conv_eff_ [private] |
Definition at line 92 of file handle_layer.h.
boost::scoped_ptr<UnitConverter> canopen::HandleLayer::conv_pos_ [private] |
Definition at line 92 of file handle_layer.h.
boost::scoped_ptr<UnitConverter> canopen::HandleLayer::conv_target_eff_ [private] |
Definition at line 91 of file handle_layer.h.
boost::scoped_ptr<UnitConverter> canopen::HandleLayer::conv_target_pos_ [private] |
Definition at line 91 of file handle_layer.h.
boost::scoped_ptr<UnitConverter> canopen::HandleLayer::conv_target_vel_ [private] |
Definition at line 91 of file handle_layer.h.
boost::scoped_ptr<UnitConverter> canopen::HandleLayer::conv_vel_ [private] |
Definition at line 92 of file handle_layer.h.
double canopen::HandleLayer::eff_ [private] |
Definition at line 86 of file handle_layer.h.
bool canopen::HandleLayer::enable_limits_ [private] |
Definition at line 126 of file handle_layer.h.
filters::FilterChain<double> canopen::HandleLayer::filter_eff_ [private] |
Definition at line 94 of file handle_layer.h.
filters::FilterChain<double> canopen::HandleLayer::filter_pos_ [private] |
Definition at line 94 of file handle_layer.h.
filters::FilterChain<double> canopen::HandleLayer::filter_vel_ [private] |
Definition at line 94 of file handle_layer.h.
boost::atomic<bool> canopen::HandleLayer::forward_command_ [private] |
Definition at line 100 of file handle_layer.h.
Definition at line 98 of file handle_layer.h.
boost::atomic<hardware_interface::JointHandle*> canopen::HandleLayer::jh_ [private] |
Definition at line 99 of file handle_layer.h.
Definition at line 98 of file handle_layer.h.
Definition at line 97 of file handle_layer.h.
Definition at line 98 of file handle_layer.h.
std::vector<LimitsHandleBase::Ptr> canopen::HandleLayer::limits_ [private] |
Definition at line 125 of file handle_layer.h.
boost::shared_ptr<canopen::MotorBase> canopen::HandleLayer::motor_ [private] |
Definition at line 85 of file handle_layer.h.
Definition at line 95 of file handle_layer.h.
double canopen::HandleLayer::pos_ [private] |
Definition at line 86 of file handle_layer.h.
Definition at line 90 of file handle_layer.h.
double canopen::HandleLayer::vel_ [private] |
Definition at line 86 of file handle_layer.h.