#include <analogue_to_position.hpp>
Public Member Functions | |
AnalogueToPosition (TiXmlElement *mapping_el, ros_ethercat_model::RobotState *robot) | |
virtual void | propagateFromRonex (ros_ethercat_model::JointState *js) |
virtual void | propagateToRonex (ros_ethercat_model::JointState *js) |
Protected Member Functions | |
bool | check_pin_in_bound_ () |
double | compute_scaled_data_ () |
virtual bool | try_init_cb_ (const ros::TimerEvent &, TiXmlElement *mapping_el, ros_ethercat_model::RobotState *robot, const char *ronex_name) |
Protected Attributes | |
GeneralIO * | general_io_ |
Pointer to the GeneralIO module we specified in the transmission. | |
double | offset_ |
size_t | pin_index_ |
index of the analogue pin | |
bool | pin_out_of_bound_ |
Is the pin inside the correct range? | |
double | scale_ |
The user can apply a scaling and offset to the raw data. |
Definition at line 37 of file analogue_to_position.hpp.
ronex::mapping::general_io::AnalogueToPosition::AnalogueToPosition | ( | TiXmlElement * | mapping_el, |
ros_ethercat_model::RobotState * | robot | ||
) |
Definition at line 34 of file analogue_to_position.cpp.
bool ronex::mapping::general_io::AnalogueToPosition::check_pin_in_bound_ | ( | ) | [protected] |
Check whether the pin is in the correct range.
Definition at line 139 of file analogue_to_position.cpp.
double ronex::mapping::general_io::AnalogueToPosition::compute_scaled_data_ | ( | ) | [protected] |
Computes the scaled data from the raw value.
Definition at line 168 of file analogue_to_position.cpp.
void ronex::mapping::general_io::AnalogueToPosition::propagateFromRonex | ( | ros_ethercat_model::JointState * | js | ) | [virtual] |
Propagating the specified analogue pin data to the given joint position.
js | joint_state of the joint specified in the transmission |
Implements ronex::RonexMapping.
Reimplemented in ronex::mapping::general_io::AnalogueToEffort.
Definition at line 128 of file analogue_to_position.cpp.
virtual void ronex::mapping::general_io::AnalogueToPosition::propagateToRonex | ( | ros_ethercat_model::JointState * | js | ) | [inline, virtual] |
This function is not doing anything as we're not propagating a command in this mapping.
Implements ronex::RonexMapping.
Definition at line 53 of file analogue_to_position.hpp.
bool ronex::mapping::general_io::AnalogueToPosition::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.
Implements ronex::RonexMapping.
Definition at line 49 of file analogue_to_position.cpp.
Pointer to the GeneralIO module we specified in the transmission.
Definition at line 57 of file analogue_to_position.hpp.
double ronex::mapping::general_io::AnalogueToPosition::offset_ [protected] |
Definition at line 64 of file analogue_to_position.hpp.
size_t ronex::mapping::general_io::AnalogueToPosition::pin_index_ [protected] |
index of the analogue pin
Definition at line 59 of file analogue_to_position.hpp.
bool ronex::mapping::general_io::AnalogueToPosition::pin_out_of_bound_ [protected] |
Is the pin inside the correct range?
Definition at line 61 of file analogue_to_position.hpp.
double ronex::mapping::general_io::AnalogueToPosition::scale_ [protected] |
The user can apply a scaling and offset to the raw data.
Definition at line 64 of file analogue_to_position.hpp.