Public Member Functions | Protected Member Functions | Protected Attributes
ronex::RonexMapping Class Reference

#include <ronex_mapping.hpp>

Inheritance diagram for ronex::RonexMapping:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void propagateFromRonex (ros_ethercat_model::JointState *js)=0
virtual void propagateToRonex (ros_ethercat_model::JointState *js)=0
 RonexMapping ()

Protected Member Functions

virtual bool try_init_cb_ (const ros::TimerEvent &, TiXmlElement *mapping_el, ros_ethercat_model::RobotState *robot, const char *ronex_name)=0

Protected Attributes

bool first_iteration_
ros::Timer init_timer_
 using a timer to initialize the transmission once we find the RoNeX we're looking for.
bool is_initialized_
 this is false until the RoNeX driver has initialised the RoNeX we're waiting for
ros::NodeHandle nh_

Detailed Description

Definition at line 33 of file ronex_mapping.hpp.


Constructor & Destructor Documentation

Definition at line 36 of file ronex_mapping.hpp.


Member Function Documentation

Propagating the data from the RoNeXes to the joint states. This function is implemented in the different mappings.

Parameters:
jsjoint_state of the joint specified in the transmission

Implemented in ronex::mapping::general_io::AnalogueToEffort, ronex::mapping::general_io::AnalogueToPosition, ronex::mapping::general_io::CommandToPWM, and ronex::mapping::general_io::CommandToPWM2PinDir.

Propagating the commands from joint states to the RoNeXes. This function is implemented in the different mappings.

Parameters:
jsjoint_state of the joint specified in the transmission

Implemented in ronex::mapping::general_io::AnalogueToPosition, ronex::mapping::general_io::CommandToPWM, and ronex::mapping::general_io::CommandToPWM2PinDir.

virtual bool ronex::RonexMapping::try_init_cb_ ( const ros::TimerEvent ,
TiXmlElement *  mapping_el,
ros_ethercat_model::RobotState robot,
const char *  ronex_name 
) [protected, pure virtual]

Timer callback for the transmission initialization. Stops the init_timer_ when the initialization is successful.

Implemented in ronex::mapping::general_io::AnalogueToPosition, ronex::mapping::general_io::CommandToPWM, and ronex::mapping::general_io::CommandToPWM2PinDir.


Member Data Documentation

Definition at line 58 of file ronex_mapping.hpp.

using a timer to initialize the transmission once we find the RoNeX we're looking for.

Definition at line 63 of file ronex_mapping.hpp.

this is false until the RoNeX driver has initialised the RoNeX we're waiting for

Definition at line 61 of file ronex_mapping.hpp.

Definition at line 57 of file ronex_mapping.hpp.


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


sr_ronex_transmissions
Author(s): Ugo Cupcic, Toni Oliver, Mark Pitchless
autogenerated on Thu Jun 6 2019 21:21:55