Public Types | Public Member Functions | Static Public Member Functions | Private Types | Private Member Functions | Private Attributes
HandleLayer Class Reference

#include <robot_layer.h>

Inheritance diagram for HandleLayer:
Inheritance graph
[legend]

List of all members.

Public Types

enum  CanSwitchResult { NotSupported, NotReadyToSwitch, ReadyToSwitch, NoNeedToSwitch }

Public Member Functions

CanSwitchResult canSwitch (const canopen::MotorBase::OperationMode &m)
void enableLimits (bool enable)
void enforceLimits (const ros::Duration &period, bool reset)
bool forwardForMode (const canopen::MotorBase::OperationMode &m)
 HandleLayer (const std::string &name, const boost::shared_ptr< canopen::MotorBase > &motor, const boost::shared_ptr< canopen::ObjectStorage > storage, XmlRpc::XmlRpcValue &options)
bool prepareFilters (canopen::LayerStatus &status)
void registerHandle (hardware_interface::JointStateInterface &iface)
hardware_interface::JointHandleregisterHandle (hardware_interface::PositionJointInterface &iface, const joint_limits_interface::JointLimits &limits, const joint_limits_interface::SoftJointLimits *soft_limits=0)
hardware_interface::JointHandleregisterHandle (hardware_interface::VelocityJointInterface &iface, const joint_limits_interface::JointLimits &limits, const joint_limits_interface::SoftJointLimits *soft_limits=0)
hardware_interface::JointHandleregisterHandle (hardware_interface::EffortJointInterface &iface, const joint_limits_interface::JointLimits &limits, const joint_limits_interface::SoftJointLimits *soft_limits=0)
bool switchMode (const canopen::MotorBase::OperationMode &m)

Static Public Member Functions

static double * assignVariable (const std::string &name, double *ptr, const std::string &req)

Private Types

typedef boost::unordered_map
< canopen::MotorBase::OperationMode,
hardware_interface::JointHandle * > 
CommandMap

Private Member Functions

template<typename T >
hardware_interface::JointHandleaddHandle (T &iface, hardware_interface::JointHandle *jh, const std::vector< canopen::MotorBase::OperationMode > &modes)
virtual void handleDiag (canopen::LayerReport &report)
virtual void handleHalt (canopen::LayerStatus &status)
virtual void handleInit (canopen::LayerStatus &status)
virtual void handleRead (canopen::LayerStatus &status, const LayerState &current_state)
virtual void handleRecover (canopen::LayerStatus &status)
virtual void handleShutdown (canopen::LayerStatus &status)
virtual void handleWrite (canopen::LayerStatus &status, const LayerState &current_state)
bool select (const canopen::MotorBase::OperationMode &m)

Private Attributes

double cmd_eff_
double cmd_pos_
double cmd_vel_
CommandMap commands_
boost::scoped_ptr< UnitConverterconv_eff_
boost::scoped_ptr< UnitConverterconv_pos_
boost::scoped_ptr< UnitConverterconv_target_eff_
boost::scoped_ptr< UnitConverterconv_target_pos_
boost::scoped_ptr< UnitConverterconv_target_vel_
boost::scoped_ptr< UnitConverterconv_vel_
double eff_
bool enable_limits_
filters::FilterChain< double > filter_eff_
filters::FilterChain< double > filter_pos_
filters::FilterChain< double > filter_vel_
boost::atomic< bool > forward_command_
hardware_interface::JointHandle jeh_
boost::atomic
< hardware_interface::JointHandle * > 
jh_
hardware_interface::JointHandle jph_
hardware_interface::JointStateHandle jsh_
hardware_interface::JointHandle jvh_
std::vector
< LimitsHandleBase::Ptr
limits_
boost::shared_ptr
< canopen::MotorBase
motor_
XmlRpc::XmlRpcValue options_
double pos_
ObjectVariables variables_
double vel_

Detailed Description

Definition at line 129 of file robot_layer.h.


Member Typedef Documentation

Definition at line 147 of file robot_layer.h.


Member Enumeration Documentation

Enumerator:
NotSupported 
NotReadyToSwitch 
ReadyToSwitch 
NoNeedToSwitch 

Definition at line 176 of file robot_layer.h.


Constructor & Destructor Documentation

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 70 of file robot_layer.cpp.


Member Function Documentation

template<typename T >
hardware_interface::JointHandle* HandleLayer::addHandle ( T &  iface,
hardware_interface::JointHandle jh,
const std::vector< canopen::MotorBase::OperationMode > &  modes 
) [inline, private]

Definition at line 150 of file robot_layer.h.

static double* HandleLayer::assignVariable ( const std::string &  name,
double *  ptr,
const std::string &  req 
) [inline, static]

Definition at line 174 of file robot_layer.h.

Definition at line 103 of file robot_layer.cpp.

void HandleLayer::enableLimits ( bool  enable)

Definition at line 289 of file robot_layer.cpp.

void HandleLayer::enforceLimits ( const ros::Duration period,
bool  reset 
)

Definition at line 282 of file robot_layer.cpp.

Definition at line 129 of file robot_layer.cpp.

virtual void HandleLayer::handleDiag ( canopen::LayerReport report) [inline, private, virtual]

Implements canopen::Layer.

Definition at line 209 of file robot_layer.h.

virtual void HandleLayer::handleHalt ( canopen::LayerStatus status) [inline, private, virtual]

Implements canopen::Layer.

Definition at line 211 of file robot_layer.h.

void HandleLayer::handleInit ( canopen::LayerStatus status) [private, virtual]

Implements canopen::Layer.

Definition at line 266 of file robot_layer.cpp.

void HandleLayer::handleRead ( canopen::LayerStatus status,
const LayerState current_state 
) [private, virtual]

Implements canopen::Layer.

Definition at line 214 of file robot_layer.cpp.

virtual void HandleLayer::handleRecover ( canopen::LayerStatus status) [inline, private, virtual]

Implements canopen::Layer.

Definition at line 212 of file robot_layer.h.

virtual void HandleLayer::handleShutdown ( canopen::LayerStatus status) [inline, private, virtual]

Implements canopen::Layer.

Definition at line 210 of file robot_layer.h.

void HandleLayer::handleWrite ( canopen::LayerStatus status,
const LayerState current_state 
) [private, virtual]

Implements canopen::Layer.

Definition at line 222 of file robot_layer.cpp.

Definition at line 260 of file robot_layer.cpp.

Definition at line 187 of file robot_layer.h.

Definition at line 175 of file robot_layer.cpp.

Definition at line 188 of file robot_layer.cpp.

Definition at line 201 of file robot_layer.cpp.

Definition at line 63 of file robot_layer.cpp.

Definition at line 115 of file robot_layer.cpp.


Member Data Documentation

double HandleLayer::cmd_eff_ [private]

Definition at line 133 of file robot_layer.h.

double HandleLayer::cmd_pos_ [private]

Definition at line 133 of file robot_layer.h.

double HandleLayer::cmd_vel_ [private]

Definition at line 133 of file robot_layer.h.

Definition at line 148 of file robot_layer.h.

boost::scoped_ptr<UnitConverter> HandleLayer::conv_eff_ [private]

Definition at line 137 of file robot_layer.h.

boost::scoped_ptr<UnitConverter> HandleLayer::conv_pos_ [private]

Definition at line 137 of file robot_layer.h.

boost::scoped_ptr<UnitConverter> HandleLayer::conv_target_eff_ [private]

Definition at line 136 of file robot_layer.h.

boost::scoped_ptr<UnitConverter> HandleLayer::conv_target_pos_ [private]

Definition at line 136 of file robot_layer.h.

boost::scoped_ptr<UnitConverter> HandleLayer::conv_target_vel_ [private]

Definition at line 136 of file robot_layer.h.

boost::scoped_ptr<UnitConverter> HandleLayer::conv_vel_ [private]

Definition at line 137 of file robot_layer.h.

double HandleLayer::eff_ [private]

Definition at line 131 of file robot_layer.h.

Definition at line 171 of file robot_layer.h.

Definition at line 139 of file robot_layer.h.

Definition at line 139 of file robot_layer.h.

Definition at line 139 of file robot_layer.h.

boost::atomic<bool> HandleLayer::forward_command_ [private]

Definition at line 145 of file robot_layer.h.

Definition at line 143 of file robot_layer.h.

Definition at line 144 of file robot_layer.h.

Definition at line 143 of file robot_layer.h.

Definition at line 142 of file robot_layer.h.

Definition at line 143 of file robot_layer.h.

Definition at line 170 of file robot_layer.h.

boost::shared_ptr<canopen::MotorBase> HandleLayer::motor_ [private]

Definition at line 130 of file robot_layer.h.

Definition at line 140 of file robot_layer.h.

double HandleLayer::pos_ [private]

Definition at line 131 of file robot_layer.h.

Definition at line 135 of file robot_layer.h.

double HandleLayer::vel_ [private]

Definition at line 131 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