Public Member Functions | Public Attributes | Static Public Attributes | Protected Member Functions | Static Protected Member Functions | Protected Attributes
RosEthercat Class Reference

#include <ros_ethercat.hpp>

Inheritance diagram for RosEthercat:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
void read (const ros::Time &time, const ros::Duration &period)
 propagate position actuator -> joint and set commands to zero
 RosEthercat ()
 RosEthercat (ros::NodeHandle &nh, const string &eth, bool allow, TiXmlElement *config)
void shutdown ()
 stop all actuators
void write (const ros::Time &time, const ros::Duration &period)
 propagate effort joint -> actuator and enforce safety limits
virtual ~RosEthercat ()

Public Attributes

string eth_
ptr_vector< EthercatHardwareethercat_hardware_
hardware_interface::EffortJointInterface joint_effort_command_interface_
hardware_interface::PositionJointInterface joint_position_command_interface_
hardware_interface::JointStateInterface joint_state_interface_
hardware_interface::VelocityJointInterface joint_velocity_command_interface_
boost::scoped_ptr
< MechStatsPublisher
mech_stats_publisher_
boost::shared_ptr
< ros_ethercat_model::RobotState
model_
ros_ethercat_model::RobotStateInterface robot_state_interface_

Static Public Attributes

static const string pid_dir = "/var/tmp/run/"

Protected Member Functions

void collect_diagnostics_loop ()
bool is_collect_diagnostics_running ()
void stop_collect_diagnostics ()

Static Protected Member Functions

static void cleanupPidFile (const char *interface)
static string generatePIDFilename (const char *interface)
static int lock_fd (int fd)
static int setupPidFile (const char *interface)

Protected Attributes

bool collect_diagnostics_running_
boost::thread collect_diagnostics_thread_
bool compatibility_mode_
std::string robot_state_name_
bool run_diagnostics_

Detailed Description

Definition at line 88 of file ros_ethercat.hpp.


Constructor & Destructor Documentation

Definition at line 91 of file ros_ethercat.hpp.

RosEthercat::RosEthercat ( ros::NodeHandle nh,
const string &  eth,
bool  allow,
TiXmlElement *  config 
) [inline]

Definition at line 99 of file ros_ethercat.hpp.

virtual RosEthercat::~RosEthercat ( ) [inline, virtual]

Definition at line 151 of file ros_ethercat.hpp.


Member Function Documentation

static void RosEthercat::cleanupPidFile ( const char *  interface) [inline, static, protected]

Definition at line 468 of file ros_ethercat.hpp.

void RosEthercat::collect_diagnostics_loop ( ) [inline, protected]

Definition at line 474 of file ros_ethercat.hpp.

static string RosEthercat::generatePIDFilename ( const char *  interface) [inline, static, protected]

Definition at line 381 of file ros_ethercat.hpp.

virtual bool RosEthercat::init ( ros::NodeHandle root_nh,
ros::NodeHandle robot_hw_nh 
) [inline, virtual]

Definition at line 169 of file ros_ethercat.hpp.

bool RosEthercat::is_collect_diagnostics_running ( ) [inline, protected]

Definition at line 495 of file ros_ethercat.hpp.

static int RosEthercat::lock_fd ( int  fd) [inline, static, protected]

Definition at line 369 of file ros_ethercat.hpp.

void RosEthercat::read ( const ros::Time time,
const ros::Duration period 
) [inline]

propagate position actuator -> joint and set commands to zero

Definition at line 279 of file ros_ethercat.hpp.

static int RosEthercat::setupPidFile ( const char *  interface) [inline, static, protected]

Definition at line 388 of file ros_ethercat.hpp.

void RosEthercat::shutdown ( ) [inline]

stop all actuators

Definition at line 332 of file ros_ethercat.hpp.

void RosEthercat::stop_collect_diagnostics ( ) [inline, protected]

Definition at line 490 of file ros_ethercat.hpp.

void RosEthercat::write ( const ros::Time time,
const ros::Duration period 
) [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 308 of file ros_ethercat.hpp.


Member Data Documentation

Definition at line 502 of file ros_ethercat.hpp.

boost::thread RosEthercat::collect_diagnostics_thread_ [protected]

Definition at line 503 of file ros_ethercat.hpp.

Definition at line 500 of file ros_ethercat.hpp.

Definition at line 352 of file ros_ethercat.hpp.

Definition at line 354 of file ros_ethercat.hpp.

Definition at line 366 of file ros_ethercat.hpp.

Definition at line 364 of file ros_ethercat.hpp.

Definition at line 361 of file ros_ethercat.hpp.

Definition at line 365 of file ros_ethercat.hpp.

Definition at line 355 of file ros_ethercat.hpp.

Definition at line 353 of file ros_ethercat.hpp.

const string RosEthercat::pid_dir = "/var/tmp/run/" [static]

Definition at line 351 of file ros_ethercat.hpp.

Definition at line 358 of file ros_ethercat.hpp.

std::string RosEthercat::robot_state_name_ [protected]

Definition at line 504 of file ros_ethercat.hpp.

Definition at line 501 of file ros_ethercat.hpp.


The documentation for this class was generated from the following file:


ros_ethercat_model
Author(s): Manos Nikolaidis
autogenerated on Thu Jul 4 2019 20:01:55