#include <command_to_pwm_2_dir_pin.hpp>
Public Member Functions | |
CommandToPWM2PinDir (TiXmlElement *mapping_el, ros_ethercat_model::RobotState *robot) | |
virtual void | propagateFromRonex (ros_ethercat_model::JointState *js) |
virtual void | propagateToRonex (ros_ethercat_model::JointState *js) |
virtual | ~CommandToPWM2PinDir () |
Protected Member Functions | |
bool | check_pins_in_bound_ () |
bool | init_ (TiXmlElement *mapping_el, ros_ethercat_model::RobotState *robot, const char *ronex_name) |
virtual bool | try_init_cb_ (const ros::TimerEvent &, TiXmlElement *mapping_el, ros_ethercat_model::RobotState *robot, const char *ronex_name) |
Protected Attributes | |
size_t | digital_pin_index_2_ |
digital pin index for the second motor direction digital pin |
Definition at line 35 of file command_to_pwm_2_dir_pin.hpp.
ronex::mapping::general_io::CommandToPWM2PinDir::CommandToPWM2PinDir | ( | TiXmlElement * | mapping_el, |
ros_ethercat_model::RobotState * | robot | ||
) |
Definition at line 36 of file command_to_pwm_2_dir_pin.cpp.
virtual ronex::mapping::general_io::CommandToPWM2PinDir::~CommandToPWM2PinDir | ( | ) | [inline, virtual] |
Definition at line 40 of file command_to_pwm_2_dir_pin.hpp.
bool ronex::mapping::general_io::CommandToPWM2PinDir::check_pins_in_bound_ | ( | ) | [protected] |
Check whether the pwm_module_ and pin_index_ are in the correct ranges.
Reimplemented from ronex::mapping::general_io::CommandToPWM.
Definition at line 98 of file command_to_pwm_2_dir_pin.cpp.
bool ronex::mapping::general_io::CommandToPWM2PinDir::init_ | ( | TiXmlElement * | mapping_el, |
ros_ethercat_model::RobotState * | robot, | ||
const char * | ronex_name | ||
) | [protected] |
Reimplemented from ronex::mapping::general_io::CommandToPWM.
Definition at line 70 of file command_to_pwm_2_dir_pin.cpp.
virtual void ronex::mapping::general_io::CommandToPWM2PinDir::propagateFromRonex | ( | ros_ethercat_model::JointState * | js | ) | [inline, virtual] |
This function is not doing anything as we're not propagating a status in this mapping.
Reimplemented from ronex::mapping::general_io::CommandToPWM.
Definition at line 45 of file command_to_pwm_2_dir_pin.hpp.
void ronex::mapping::general_io::CommandToPWM2PinDir::propagateToRonex | ( | ros_ethercat_model::JointState * | js | ) | [virtual] |
Propagating the specified joint command to the given PWM module.
js | joint_state of the joint specified in the transmission |
Reimplemented from ronex::mapping::general_io::CommandToPWM.
Definition at line 126 of file command_to_pwm_2_dir_pin.cpp.
bool ronex::mapping::general_io::CommandToPWM2PinDir::try_init_cb_ | ( | const ros::TimerEvent & | , |
TiXmlElement * | mapping_el, | ||
ros_ethercat_model::RobotState * | robot, | ||
const char * | ronex_name | ||
) | [protected, virtual] |
Timer callback for the transmission initialization. Stops the init_timer_ when the initialization is successful.
Reimplemented from ronex::mapping::general_io::CommandToPWM.
Definition at line 54 of file command_to_pwm_2_dir_pin.cpp.
size_t ronex::mapping::general_io::CommandToPWM2PinDir::digital_pin_index_2_ [protected] |
digital pin index for the second motor direction digital pin
Definition at line 56 of file command_to_pwm_2_dir_pin.hpp.