Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
SVHDiagnostics Class Reference

#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::SVHFingerManagerm_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...
 

Detailed Description

Definition at line 70 of file SVHDiagnostics.h.

Member Enumeration Documentation

◆ diag_information

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.

Constructor & Destructor Documentation

◆ SVHDiagnostics()

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.

Parameters
nhROS Nodehandle
finger_managerHandle to the SVH finger manager for library access
enable_ros_contol_loopfunction handle to set the ros-control-loop enabling flag
init_controller_parametersfunction handle to get the hand parameters
nameaction 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::~SVHDiagnostics ( )

Default DTOR.

Definition at line 63 of file SVHDiagnostics.cpp.

Member Function Documentation

◆ basicTestCallback()

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.

◆ debugOuput()

void SVHDiagnostics::debugOuput ( )
private

debugOutput prints the diagnostic data of all finger

Definition at line 401 of file SVHDiagnostics.cpp.

◆ evaluateBasicTest()

schunk_svh_msgs::SVHDiagnosticsResult SVHDiagnostics::evaluateBasicTest ( )
private

evaluateBasicTest evaluates the diagnostics status of the basic test to send the hint informations to the webside

Returns
std_msgs::UInt8MultiArray mesg with the test results

Definition at line 230 of file SVHDiagnostics.cpp.

◆ initializeProtocolMessage()

void SVHDiagnostics::initializeProtocolMessage ( )
private

initialize the protocol variables

Definition at line 473 of file SVHDiagnostics.cpp.

◆ initTest()

void SVHDiagnostics::initTest ( )
private

initialize the protocol variables

Definition at line 68 of file SVHDiagnostics.cpp.

◆ qualityProtocolWritting()

void SVHDiagnostics::qualityProtocolWritting ( )
private

set the protocol variables

Definition at line 445 of file SVHDiagnostics.cpp.

◆ resetDiagnosticStatus()

void SVHDiagnostics::resetDiagnosticStatus ( )
private

resetDiagnosticStatus resets the finger vector with the diagnostic data

Definition at line 386 of file SVHDiagnostics.cpp.

◆ testCallback()

void SVHDiagnostics::testCallback ( const std_msgs::String &  )

Callback function to test the subfunctions of SVHDiagnostics.

Member Data Documentation

◆ channel_currents

std_msgs::Float64MultiArray SVHDiagnostics::channel_currents
private

Current Value message template.

Definition at line 164 of file SVHDiagnostics.h.

◆ channel_pos_

sensor_msgs::JointState SVHDiagnostics::channel_pos_
private

joint state message template

Definition at line 161 of file SVHDiagnostics.h.

◆ m_action_feedback

schunk_svh_msgs::SVHDiagnosticsFeedback SVHDiagnostics::m_action_feedback
private

Definition at line 195 of file SVHDiagnostics.h.

◆ m_action_name

std::string SVHDiagnostics::m_action_name
private

Definition at line 201 of file SVHDiagnostics.h.

◆ m_action_result

schunk_svh_msgs::SVHDiagnosticsResult SVHDiagnostics::m_action_result
private

Action result.

Definition at line 198 of file SVHDiagnostics.h.

◆ m_assembly_of

std::string SVHDiagnostics::m_assembly_of
private

Name of the testing person.

Definition at line 173 of file SVHDiagnostics.h.

◆ m_basic_test_running

bool SVHDiagnostics::m_basic_test_running
private

To catch multiple bastic test starts.

Definition at line 183 of file SVHDiagnostics.h.

◆ m_communication

bool SVHDiagnostics::m_communication
private

Type of onnection.

Definition at line 180 of file SVHDiagnostics.h.

◆ m_connect_retry_count

int SVHDiagnostics::m_connect_retry_count
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.

◆ m_diagnostics_action_server

actionlib::SimpleActionServer<schunk_svh_msgs::SVHDiagnosticsAction> SVHDiagnostics::m_diagnostics_action_server
private

Action Server.

Definition at line 192 of file SVHDiagnostics.h.

◆ m_enable_ros_contol_loop

std::function<void(bool)> SVHDiagnostics::m_enable_ros_contol_loop
private

function handle to set the ros-control-loop enabling flag in the SVHWrapper

Definition at line 141 of file SVHDiagnostics.h.

◆ m_execution_L

bool SVHDiagnostics::m_execution_L
private

Definition at line 177 of file SVHDiagnostics.h.

◆ m_execution_R

bool SVHDiagnostics::m_execution_R
private

Type of the Hand, No/ L / R.

Definition at line 176 of file SVHDiagnostics.h.

◆ m_finger_manager

std::shared_ptr<driver_svh::SVHFingerManager> SVHDiagnostics::m_finger_manager
private

Handle to the SVH finger manager for library access.

Definition at line 136 of file SVHDiagnostics.h.

◆ m_init_controller_parameters

std::function<void(uint16_t, uint16_t)> SVHDiagnostics::m_init_controller_parameters
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.

◆ m_msg_protocol_variable

schunk_svh_msgs::SVHDiagnosticsToProtocol SVHDiagnostics::m_msg_protocol_variable
private

Message for the Protocol variable.

Definition at line 189 of file SVHDiagnostics.h.

◆ m_priv_nh

ros::NodeHandle SVHDiagnostics::m_priv_nh
private

private node handle

Definition at line 102 of file SVHDiagnostics.h.

◆ m_pub_protocol_variables

ros::Publisher SVHDiagnostics::m_pub_protocol_variables
private

publisher to the protocol variables

Definition at line 186 of file SVHDiagnostics.h.

◆ m_serial_device_name

std::string SVHDiagnostics::m_serial_device_name
private

Serial device to use for communication with hardware.

Definition at line 150 of file SVHDiagnostics.h.

◆ m_serial_no

std::string SVHDiagnostics::m_serial_no
private

Serial No of the tested Hand.

Definition at line 170 of file SVHDiagnostics.h.

◆ name_prefix

std::string SVHDiagnostics::name_prefix
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.

◆ reset_success

std::vector<bool> SVHDiagnostics::reset_success
private

Reset successed vector.

Definition at line 167 of file SVHDiagnostics.h.


The documentation for this class was generated from the following files:


schunk_svh_driver
Author(s): Georg Heppner , Felix Exner , Pascal Becker , Johannes Mangler
autogenerated on Sat Apr 15 2023 02:24:55