#include <ronex_mapping.hpp>
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_ |
Definition at line 33 of file ronex_mapping.hpp.
ronex::RonexMapping::RonexMapping | ( | ) | [inline] |
Definition at line 36 of file ronex_mapping.hpp.
virtual void ronex::RonexMapping::propagateFromRonex | ( | ros_ethercat_model::JointState * | js | ) | [pure virtual] |
Propagating the data from the RoNeXes to the joint states. This function is implemented in the different mappings.
js | joint_state of the joint specified in the transmission |
Implemented in ronex::mapping::general_io::AnalogueToEffort, ronex::mapping::general_io::AnalogueToPosition, and ronex::mapping::general_io::CommandToPWM.
virtual void ronex::RonexMapping::propagateToRonex | ( | ros_ethercat_model::JointState * | js | ) | [pure virtual] |
Propagating the commands from joint states to the RoNeXes. This function is implemented in the different mappings.
js | joint_state of the joint specified in the transmission |
Implemented in ronex::mapping::general_io::AnalogueToPosition, and ronex::mapping::general_io::CommandToPWM.
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, and ronex::mapping::general_io::CommandToPWM.
bool ronex::RonexMapping::first_iteration_ [protected] |
Definition at line 58 of file ronex_mapping.hpp.
ros::Timer ronex::RonexMapping::init_timer_ [protected] |
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.
bool ronex::RonexMapping::is_initialized_ [protected] |
this is false until the RoNeX driver has initialised the RoNeX we're waiting for
Definition at line 61 of file ronex_mapping.hpp.
ros::NodeHandle ronex::RonexMapping::nh_ [protected] |
Definition at line 57 of file ronex_mapping.hpp.