Functions | Variables
halt_detector.cpp File Reference
#include <ros/ros.h>
#include <cob_base_controller_utils/WheelCommands.h>
#include <controller_manager_msgs/SwitchController.h>
#include <diagnostic_msgs/DiagnosticArray.h>
#include <geometry_msgs/Twist.h>
#include <std_srvs/Trigger.h>
Include dependency graph for halt_detector.cpp:

Go to the source code of this file.

Functions

void baseCommandsCallback (const geometry_msgs::Twist::ConstPtr &msg)
 
bool containsSubstring (std::string string, std::string substring)
 
void diagnosticsAggCallback (const diagnostic_msgs::DiagnosticArray::ConstPtr &msg)
 
void halt ()
 
void haltAfterStopTimeoutCallback (const ros::TimerEvent &)
 
int main (int argc, char *argv[])
 
void recover ()
 
void recoverAfterStuckCallback (const ros::TimerEvent &)
 
void switch_controllers ()
 
void wheelCommandsCallback (const cob_base_controller_utils::WheelCommands::ConstPtr &msg)
 

Variables

std::vector< std::string > g_controller_spawn
 
std::vector< std::string > g_diagnostic_recovery_trigger
 
ros::ServiceClient g_halt_client
 
bool g_is_stopped
 
bool g_is_stuck
 
ros::Time g_last_diagnostic_recover_timestamp
 
std::vector< ros::Timeg_last_wheel_commands_ok
 
ros::Duration g_recover_after_stuck_timeout
 
ros::Timer g_recover_after_stuck_timer
 
ros::ServiceClient g_recover_client
 
bool g_recovering
 
double g_stop_threshold
 
ros::Duration g_stop_timeout
 
ros::Timer g_stop_timer
 
bool g_stuck_possible
 
double g_stuck_threshold
 
ros::Duration g_stuck_timeout
 
ros::ServiceClient g_switch_controller_client
 

Function Documentation

◆ baseCommandsCallback()

void baseCommandsCallback ( const geometry_msgs::Twist::ConstPtr &  msg)

Callback for base command twists.

Restarts the stop_timer if twist exceeds the threshold. Additionally recovers the base if a twist exceeds the threshold, the base ist not stuck and not yet recovered.

Parameters
msgTwist message.

Definition at line 223 of file halt_detector.cpp.

◆ containsSubstring()

bool containsSubstring ( std::string  string,
std::string  substring 
)

Checks if a substring is present in a string.

Parameters
stringString which is checked.
substringString which is searched.
Returns
Tue if substring is present, false otherwise.

Definition at line 121 of file halt_detector.cpp.

◆ diagnosticsAggCallback()

void diagnosticsAggCallback ( const diagnostic_msgs::DiagnosticArray::ConstPtr &  msg)

Callback for diagnostic aggregation.

Recovers on diagnostic errors if currently not stuck.

Parameters
msgDiagnosticArray message.

Definition at line 136 of file halt_detector.cpp.

◆ halt()

void halt ( )

Halt the base.

Definition at line 85 of file halt_detector.cpp.

◆ haltAfterStopTimeoutCallback()

void haltAfterStopTimeoutCallback ( const ros::TimerEvent )

Callback for the stop timer.

Definition at line 94 of file halt_detector.cpp.

◆ main()

int main ( int  argc,
char *  argv[] 
)

Definition at line 243 of file halt_detector.cpp.

◆ recover()

void recover ( )

Recover the base.

Definition at line 69 of file halt_detector.cpp.

◆ recoverAfterStuckCallback()

void recoverAfterStuckCallback ( const ros::TimerEvent )

Callback for the recover timer after stuck.

Definition at line 104 of file halt_detector.cpp.

◆ switch_controllers()

void switch_controllers ( )

Reload the controllers.

Definition at line 49 of file halt_detector.cpp.

◆ wheelCommandsCallback()

void wheelCommandsCallback ( const cob_base_controller_utils::WheelCommands::ConstPtr &  msg)

Callback for wheel commands.

Calls a halt if the error of the wheel commands exceeded set threshold for set timeout.

Parameters
msgWheelCommands message.

Definition at line 176 of file halt_detector.cpp.

Variable Documentation

◆ g_controller_spawn

std::vector<std::string> g_controller_spawn

Definition at line 28 of file halt_detector.cpp.

◆ g_diagnostic_recovery_trigger

std::vector<std::string> g_diagnostic_recovery_trigger

Definition at line 42 of file halt_detector.cpp.

◆ g_halt_client

ros::ServiceClient g_halt_client

Definition at line 25 of file halt_detector.cpp.

◆ g_is_stopped

bool g_is_stopped

Definition at line 39 of file halt_detector.cpp.

◆ g_is_stuck

bool g_is_stuck

Definition at line 40 of file halt_detector.cpp.

◆ g_last_diagnostic_recover_timestamp

ros::Time g_last_diagnostic_recover_timestamp

Definition at line 33 of file halt_detector.cpp.

◆ g_last_wheel_commands_ok

std::vector<ros::Time> g_last_wheel_commands_ok

Definition at line 32 of file halt_detector.cpp.

◆ g_recover_after_stuck_timeout

ros::Duration g_recover_after_stuck_timeout

Definition at line 31 of file halt_detector.cpp.

◆ g_recover_after_stuck_timer

ros::Timer g_recover_after_stuck_timer

Definition at line 35 of file halt_detector.cpp.

◆ g_recover_client

ros::ServiceClient g_recover_client

Definition at line 26 of file halt_detector.cpp.

◆ g_recovering

bool g_recovering

Definition at line 38 of file halt_detector.cpp.

◆ g_stop_threshold

double g_stop_threshold

Definition at line 37 of file halt_detector.cpp.

◆ g_stop_timeout

ros::Duration g_stop_timeout

Definition at line 29 of file halt_detector.cpp.

◆ g_stop_timer

ros::Timer g_stop_timer

Definition at line 34 of file halt_detector.cpp.

◆ g_stuck_possible

bool g_stuck_possible

Definition at line 41 of file halt_detector.cpp.

◆ g_stuck_threshold

double g_stuck_threshold

Definition at line 36 of file halt_detector.cpp.

◆ g_stuck_timeout

ros::Duration g_stuck_timeout

Definition at line 30 of file halt_detector.cpp.

◆ g_switch_controller_client

ros::ServiceClient g_switch_controller_client

Definition at line 27 of file halt_detector.cpp.



cob_base_controller_utils
Author(s): Felix Messmer , Mathias Lüdtke
autogenerated on Mon May 1 2023 02:44:16