#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 |
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 33 of file motor_data_checker.cpp.
generic_updater::MotorDataChecker::~MotorDataChecker | ( | ) |
Definition at line 40 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 | ||
) |
Definition at line 87 of file motor_data_checker.cpp.
|
protected |
Definition at line 152 of file motor_data_checker.cpp.
void generic_updater::MotorDataChecker::init | ( | std::vector< shadow_joints::Joint > | joints_vector, |
std::vector< UpdateConfig > | initialization_configs_vector | ||
) |
Definition at line 51 of file motor_data_checker.cpp.
|
protected |
Definition at line 129 of file motor_data_checker.cpp.
|
protected |
Definition at line 164 of file motor_data_checker.cpp.
|
protected |
Definition at line 131 of file motor_data_checker.hpp.
|
protected |
Definition at line 133 of file motor_data_checker.hpp.
|
protected |
Definition at line 141 of file motor_data_checker.hpp.
|
protected |
Definition at line 130 of file motor_data_checker.hpp.
|
staticprotected |
Definition at line 129 of file motor_data_checker.hpp.
|
protected |
Definition at line 132 of file motor_data_checker.hpp.