#include <SVHDiagnostics.h>
Public Member Functions | |
| void | basicTestCallback (const schunk_svh_msgs::SVHDiagnosticsGoalConstPtr &goal) |
| SVHDiagnostics (const ros::NodeHandle &nh, std::shared_ptr< driver_svh::SVHFingerManager > &finger_manager, std::function< void(bool)> enable_ros_contol_loop, std::function< void(uint16_t, uint16_t)> init_controller_parameters, std::string name) | |
| SVHDiagnostics constructs a new node object that handles most of the functionality. More... | |
| void | testCallback (const std_msgs::String &) |
| Callback function to test the subfunctions of SVHDiagnostics. More... | |
| ~SVHDiagnostics () | |
| Default DTOR. More... | |
Private Types | |
| enum | diag_information { zero_defect, board_one, board_two, board_one_encoder, board_one_motor, board_two_encoder, board_two_motor, encoder_motor, encoder, motor, current_range, position_range, diag_information_dimension } |
Private Member Functions | |
| void | debugOuput () |
| debugOutput prints the diagnostic data of all finger More... | |
| schunk_svh_msgs::SVHDiagnosticsResult | evaluateBasicTest () |
| evaluateBasicTest evaluates the diagnostics status of the basic test to send the hint informations to the webside More... | |
| void | initializeProtocolMessage () |
| initialize the protocol variables More... | |
| void | initTest () |
| initialize the protocol variables More... | |
| void | qualityProtocolWritting () |
| set the protocol variables More... | |
| void | resetDiagnosticStatus () |
| resetDiagnosticStatus resets the finger vector with the diagnostic data More... | |
Private Attributes | |
| std_msgs::Float64MultiArray | channel_currents |
| Current Value message template. More... | |
| sensor_msgs::JointState | channel_pos_ |
| joint state message template More... | |
| schunk_svh_msgs::SVHDiagnosticsFeedback | m_action_feedback |
| std::string | m_action_name |
| schunk_svh_msgs::SVHDiagnosticsResult | m_action_result |
| Action result. More... | |
| std::string | m_assembly_of |
| Name of the testing person. More... | |
| bool | m_basic_test_running |
| To catch multiple bastic test starts. More... | |
| bool | m_communication |
| Type of onnection. More... | |
| int | m_connect_retry_count |
| actionlib::SimpleActionServer< schunk_svh_msgs::SVHDiagnosticsAction > | m_diagnostics_action_server |
| Action Server. More... | |
| std::function< void(bool)> | m_enable_ros_contol_loop |
| bool | m_execution_L |
| bool | m_execution_R |
| Type of the Hand, No/ L / R. More... | |
| std::shared_ptr< driver_svh::SVHFingerManager > | m_finger_manager |
| Handle to the SVH finger manager for library access. More... | |
| std::function< void(uint16_t, uint16_t)> | m_init_controller_parameters |
| schunk_svh_msgs::SVHDiagnosticsToProtocol | m_msg_protocol_variable |
| Message for the Protocol variable. More... | |
| ros::NodeHandle | m_priv_nh |
| private node handle More... | |
| ros::Publisher | m_pub_protocol_variables |
| publisher to the protocol variables More... | |
| std::string | m_serial_device_name |
| Serial device to use for communication with hardware. More... | |
| std::string | m_serial_no |
| Serial No of the tested Hand. More... | |
| std::string | name_prefix |
| std::vector< bool > | reset_success |
| Reset successed vector. More... | |
Definition at line 70 of file SVHDiagnostics.h.
|
private |
| Enumerator | |
|---|---|
| zero_defect | |
| board_one | |
| board_two | |
| board_one_encoder | |
| board_one_motor | |
| board_two_encoder | |
| board_two_motor | |
| encoder_motor | |
| encoder | |
| motor | |
| current_range | |
| position_range | |
| diag_information_dimension | |
Definition at line 203 of file SVHDiagnostics.h.
| SVHDiagnostics::SVHDiagnostics | ( | const ros::NodeHandle & | nh, |
| std::shared_ptr< driver_svh::SVHFingerManager > & | finger_manager, | ||
| std::function< void(bool)> | enable_ros_contol_loop, | ||
| std::function< void(uint16_t, uint16_t)> | init_controller_parameters, | ||
| std::string | name | ||
| ) |
SVHDiagnostics constructs a new node object that handles most of the functionality.
| nh | ROS Nodehandle |
| finger_manager | Handle to the SVH finger manager for library access |
| enable_ros_contol_loop | function handle to set the ros-control-loop enabling flag |
| init_controller_parameters | function handle to get the hand parameters |
| name | action server name |
m_pub_protocol_variables pubished the diagnostic results to the SVHProtocol Node to print the Test-Protocol
Definition at line 35 of file SVHDiagnostics.cpp.
| SVHDiagnostics::~SVHDiagnostics | ( | ) |
Default DTOR.
Definition at line 63 of file SVHDiagnostics.cpp.
| void SVHDiagnostics::basicTestCallback | ( | const schunk_svh_msgs::SVHDiagnosticsGoalConstPtr & | goal | ) |
Callback function to conduct the basic test for the SCHUNK five finger hand (msg defined in schunk_web_gui/msg/DiagnosticsMsg.msg)
Definition at line 115 of file SVHDiagnostics.cpp.
|
private |
debugOutput prints the diagnostic data of all finger
Definition at line 401 of file SVHDiagnostics.cpp.
|
private |
evaluateBasicTest evaluates the diagnostics status of the basic test to send the hint informations to the webside
Definition at line 230 of file SVHDiagnostics.cpp.
|
private |
initialize the protocol variables
Definition at line 473 of file SVHDiagnostics.cpp.
|
private |
initialize the protocol variables
Definition at line 68 of file SVHDiagnostics.cpp.
|
private |
set the protocol variables
Definition at line 445 of file SVHDiagnostics.cpp.
|
private |
resetDiagnosticStatus resets the finger vector with the diagnostic data
Definition at line 386 of file SVHDiagnostics.cpp.
| void SVHDiagnostics::testCallback | ( | const std_msgs::String & | ) |
Callback function to test the subfunctions of SVHDiagnostics.
|
private |
Current Value message template.
Definition at line 164 of file SVHDiagnostics.h.
|
private |
joint state message template
Definition at line 161 of file SVHDiagnostics.h.
|
private |
Definition at line 195 of file SVHDiagnostics.h.
|
private |
Definition at line 201 of file SVHDiagnostics.h.
|
private |
Action result.
Definition at line 198 of file SVHDiagnostics.h.
|
private |
Name of the testing person.
Definition at line 173 of file SVHDiagnostics.h.
|
private |
To catch multiple bastic test starts.
Definition at line 183 of file SVHDiagnostics.h.
|
private |
Type of onnection.
Definition at line 180 of file SVHDiagnostics.h.
|
private |
Number of times the connect routine tries to connect in case that we receive at least one package
Definition at line 154 of file SVHDiagnostics.h.
|
private |
Action Server.
Definition at line 192 of file SVHDiagnostics.h.
|
private |
function handle to set the ros-control-loop enabling flag in the SVHWrapper
Definition at line 141 of file SVHDiagnostics.h.
|
private |
Definition at line 177 of file SVHDiagnostics.h.
|
private |
Type of the Hand, No/ L / R.
Definition at line 176 of file SVHDiagnostics.h.
|
private |
Handle to the SVH finger manager for library access.
Definition at line 136 of file SVHDiagnostics.h.
|
private |
function handle to get the hand parameters from ros-param-server and set them to the finger_manager to have cleared parameter set
Definition at line 147 of file SVHDiagnostics.h.
|
private |
Message for the Protocol variable.
Definition at line 189 of file SVHDiagnostics.h.
|
private |
private node handle
Definition at line 102 of file SVHDiagnostics.h.
|
private |
publisher to the protocol variables
Definition at line 186 of file SVHDiagnostics.h.
|
private |
Serial device to use for communication with hardware.
Definition at line 150 of file SVHDiagnostics.h.
|
private |
Serial No of the tested Hand.
Definition at line 170 of file SVHDiagnostics.h.
|
private |
Prefix for the driver to identify joint names if the Driver should expext "left_hand_Pinky" than the prefix is left_hand
Definition at line 158 of file SVHDiagnostics.h.
|
private |
Reset successed vector.
Definition at line 167 of file SVHDiagnostics.h.