#include <motor_data_checker.hpp>
Public Member Functions | |
bool | check_message (boost::ptr_vector< shadow_joints::Joint >::iterator joint_tmp, FROM_MOTOR_DATA_TYPE motor_data_type, int16u motor_slow_data_type) |
void | init (boost::ptr_vector< shadow_joints::Joint > joints_vector, std::vector< UpdateConfig > initialization_configs_vector) |
MotorDataChecker (boost::ptr_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 | ( | boost::ptr_vector< shadow_joints::Joint > | joints_vector, |
std::vector< UpdateConfig > | initialization_configs_vector | ||
) |
Definition at line 33 of file motor_data_checker.cpp.
Definition at line 40 of file motor_data_checker.cpp.
bool generic_updater::MotorDataChecker::check_message | ( | boost::ptr_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 iterator containing the data of the joint the type of the received data the type of the received sub-data (used if the motor_data_type is MOTOR_DATA_SLOW_MISC)
Definition at line 84 of file motor_data_checker.cpp.
int generic_updater::MotorDataChecker::find | ( | FROM_MOTOR_DATA_TYPE | motor_data_type | ) | [protected] |
Definition at line 145 of file motor_data_checker.cpp.
void generic_updater::MotorDataChecker::init | ( | boost::ptr_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
the vector with the joints (motors) from which information is coming vector containing the initialization commands whose answers need to be checked
Definition at line 51 of file motor_data_checker.cpp.
bool generic_updater::MotorDataChecker::is_everything_checked | ( | ) | [protected] |
Definition at line 122 of file motor_data_checker.cpp.
void generic_updater::MotorDataChecker::timer_callback | ( | const ros::TimerEvent & | event | ) | [protected] |
Definition at line 155 of file motor_data_checker.cpp.
Definition at line 130 of file motor_data_checker.hpp.
Definition at line 132 of file motor_data_checker.hpp.
Definition at line 138 of file motor_data_checker.hpp.
Definition at line 129 of file motor_data_checker.hpp.
const double generic_updater::MotorDataChecker::timeout = 5.0 [static, protected] |
Definition at line 128 of file motor_data_checker.hpp.
operation_mode::device_update_state::DeviceUpdateState generic_updater::MotorDataChecker::update_state [protected] |
Definition at line 131 of file motor_data_checker.hpp.