#include <motor_data_checker.hpp>
Public Member Functions | |
bool | check_message (std::vector< shadow_joints::Joint >::iterator joint_tmp, FROM_MOTOR_DATA_TYPE motor_data_type, int16u motor_slow_data_type) |
void | init (std::vector< shadow_joints::Joint > joints_vector, std::vector< UpdateConfig > initialization_configs_vector) |
MotorDataChecker (std::vector< shadow_joints::Joint > joints_vector, std::vector< UpdateConfig > initialization_configs_vector) | |
~MotorDataChecker () | |
Protected Member Functions | |
int | find (FROM_MOTOR_DATA_TYPE motor_data_type) |
bool | is_everything_checked () |
void | timer_callback (const ros::TimerEvent &event) |
Protected Attributes | |
ros::Timer | check_timeout_timer |
ros::Duration | init_max_duration |
std::vector< MessageChecker > | msg_checkers_ |
ros::NodeHandle | nh_tilde |
operation_mode::device_update_state::DeviceUpdateState | update_state |
Static Protected Attributes | |
static const double | timeout = 5.0 |
MotorDataChecker checks if all expected messages from the motors have been received
Definition at line 96 of file motor_data_checker.hpp.
generic_updater::MotorDataChecker::MotorDataChecker | ( | std::vector< shadow_joints::Joint > | joints_vector, |
std::vector< UpdateConfig > | initialization_configs_vector | ||
) |
Definition at line 34 of file motor_data_checker.cpp.
Definition at line 41 of file motor_data_checker.cpp.
bool generic_updater::MotorDataChecker::check_message | ( | std::vector< shadow_joints::Joint >::iterator | joint_tmp, |
FROM_MOTOR_DATA_TYPE | motor_data_type, | ||
int16u | motor_slow_data_type | ||
) |
Checks the message as received. Checking if we received the specified motor_data_type or the motor_slow_data_type. Checks a certain message coming from a certain joint (motor) Joints without a motor are not expected to provide any information
joint_tmp | joint iterator containing the data of the joint |
motor_data_type | the type of the received data |
motor_slow_data_type | the type of the received sub-data (used if the motor_data_type is MOTOR_DATA_SLOW_MISC) |
Definition at line 88 of file motor_data_checker.cpp.
int generic_updater::MotorDataChecker::find | ( | FROM_MOTOR_DATA_TYPE | motor_data_type | ) | [protected] |
Definition at line 153 of file motor_data_checker.cpp.
void generic_updater::MotorDataChecker::init | ( | std::vector< shadow_joints::Joint > | joints_vector, |
std::vector< UpdateConfig > | initialization_configs_vector | ||
) |
Initializes the Motor Data Checker to the not received state for each message Should be used when reinitializing
joints_vector | the vector with the joints (motors) from which information is coming |
initialization_configs_vector | vector containing the initialization commands whose answers need to be checked |
Definition at line 52 of file motor_data_checker.cpp.
bool generic_updater::MotorDataChecker::is_everything_checked | ( | ) | [protected] |
Definition at line 130 of file motor_data_checker.cpp.
void generic_updater::MotorDataChecker::timer_callback | ( | const ros::TimerEvent & | event | ) | [protected] |
Definition at line 165 of file motor_data_checker.cpp.
Definition at line 131 of file motor_data_checker.hpp.
Definition at line 133 of file motor_data_checker.hpp.
std::vector<MessageChecker> generic_updater::MotorDataChecker::msg_checkers_ [protected] |
Definition at line 141 of file motor_data_checker.hpp.
Definition at line 130 of file motor_data_checker.hpp.
const double generic_updater::MotorDataChecker::timeout = 5.0 [static, protected] |
Definition at line 129 of file motor_data_checker.hpp.
operation_mode::device_update_state::DeviceUpdateState generic_updater::MotorDataChecker::update_state [protected] |
Definition at line 132 of file motor_data_checker.hpp.