#include <ros_ethercat.hpp>

Public Member Functions | |
| void | read () |
| propagate position actuator -> joint and set commands to zero | |
| RosEthercat (ros::NodeHandle &nh, const string ð, bool allow, TiXmlElement *config) | |
| void | shutdown () |
| stop all actuators | |
| void | write () |
| propagate effort joint -> actuator and enforce safety limits | |
| virtual | ~RosEthercat () |
Public Attributes | |
| ros::NodeHandle | cm_node_ |
| EthercatHardware | ec_ |
| hardware_interface::EffortJointInterface | effort_joint_interface_ |
| hardware_interface::JointCommandInterface | joint_command_interface_ |
| hardware_interface::JointStateInterface | joint_state_interface_ |
| boost::scoped_ptr < MechStatsPublisher > | mech_stats_publisher_ |
| ros_ethercat_model::RobotState | model_ |
| hardware_interface::PositionJointInterface | position_joint_interface_ |
Definition at line 80 of file ros_ethercat.hpp.
| RosEthercat::RosEthercat | ( | ros::NodeHandle & | nh, |
| const string & | eth, | ||
| bool | allow, | ||
| TiXmlElement * | config | ||
| ) | [inline] |
Definition at line 83 of file ros_ethercat.hpp.
| virtual RosEthercat::~RosEthercat | ( | ) | [inline, virtual] |
Definition at line 114 of file ros_ethercat.hpp.
| void RosEthercat::read | ( | ) | [inline] |
propagate position actuator -> joint and set commands to zero
Definition at line 119 of file ros_ethercat.hpp.
| void RosEthercat::shutdown | ( | ) | [inline] |
stop all actuators
Definition at line 152 of file ros_ethercat.hpp.
| void RosEthercat::write | ( | ) | [inline] |
propagate effort joint -> actuator and enforce safety limits
Modify the commanded_effort_ of each joint state so that the joint limits are satisfied
Definition at line 136 of file ros_ethercat.hpp.
Definition at line 163 of file ros_ethercat.hpp.
| EthercatHardware RosEthercat::ec_ |
Definition at line 165 of file ros_ethercat.hpp.
Definition at line 170 of file ros_ethercat.hpp.
Definition at line 169 of file ros_ethercat.hpp.
Definition at line 168 of file ros_ethercat.hpp.
| boost::scoped_ptr<MechStatsPublisher> RosEthercat::mech_stats_publisher_ |
Definition at line 166 of file ros_ethercat.hpp.
Definition at line 164 of file ros_ethercat.hpp.
Definition at line 171 of file ros_ethercat.hpp.