#include <transmission.hpp>
Public Member Functions | |
virtual bool | initXml (TiXmlElement *config, RobotState *robot) |
Initializes the transmission from XML data. | |
virtual void | propagateEffort () |
Uses commanded joint efforts to fill out commanded motor currents. | |
virtual void | propagatePosition () |
Uses encoder data to fill out joint position and velocities. | |
virtual | ~Transmission () |
Destructor. | |
Public Attributes | |
Actuator * | actuator_ |
JointState * | joint_ |
std::string | name_ |
the name of the transmission |
Definition at line 50 of file transmission.hpp.
virtual ros_ethercat_model::Transmission::~Transmission | ( | ) | [inline, virtual] |
Destructor.
Definition at line 55 of file transmission.hpp.
virtual bool ros_ethercat_model::Transmission::initXml | ( | TiXmlElement * | config, |
RobotState * | robot | ||
) | [inline, virtual] |
Initializes the transmission from XML data.
Definition at line 61 of file transmission.hpp.
virtual void ros_ethercat_model::Transmission::propagateEffort | ( | ) | [inline, virtual] |
Uses commanded joint efforts to fill out commanded motor currents.
Definition at line 74 of file transmission.hpp.
virtual void ros_ethercat_model::Transmission::propagatePosition | ( | ) | [inline, virtual] |
Uses encoder data to fill out joint position and velocities.
Definition at line 69 of file transmission.hpp.
The actuator that this transmission handles. Child classes may add more actuators if they need them.
Definition at line 88 of file transmission.hpp.
The state of the main joint that this transmission handles. Child classes may add more joints if they need them. JointState object owned by RobotState object.
Definition at line 84 of file transmission.hpp.
std::string ros_ethercat_model::Transmission::name_ |
the name of the transmission
Definition at line 76 of file transmission.hpp.