#include <IOwd_ros.h>
|
| | IOWatchdogROS (ros::NodeHandle *nh, VMXPi *vmx) |
| | Constructs the IOWatchdogROS object. More...
|
| |
| | ~IOWatchdogROS () |
| | Destructor for the IOWatchdogROS object. More...
|
| |
| bool | SetStatus (std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res) |
| | Provides the ROS service to enable or disable the IO Watchdog when this service is called on the io_watchdog/status server. More...
|
| |
| void | Run_t () |
| | Provides a method to regularly "feed" the IO Watchdog while it is enabled before the watchdog timeout period (250ms). If the IO Watchdog is not fed within the timeout period or has expired, the VMXErrorCode will be returned. More...
|
| |
| void | Disable () |
| | Disables all IO Watchdog managed outputs and displays the error code via the pointer to the VMXErrorCode. More...
|
| |
| void | DisplayVMXError (VMXErrorCode vmxerr) |
| | Displays the VMXError. More...
|
| |
◆ IOWatchdogROS()
| IOWatchdogROS::IOWatchdogROS |
( |
ros::NodeHandle * |
nh, |
|
|
VMXPi * |
vmx |
|
) |
| |
Constructs the IOWatchdogROS object.
- Parameters
-
| nh | Internal reference to the ROS node that the program will use to interact with the ROS system. |
| vmx | VMX-pi parameter used to initialize the VMX-pi HAL. |
◆ ~IOWatchdogROS()
| IOWatchdogROS::~IOWatchdogROS |
( |
| ) |
|
◆ Disable()
| void IOWatchdogROS::Disable |
( |
| ) |
|
Disables all IO Watchdog managed outputs and displays the error code via the pointer to the VMXErrorCode.
◆ Run_t()
| void IOWatchdogROS::Run_t |
( |
| ) |
|
Provides a method to regularly "feed" the IO Watchdog while it is enabled before the watchdog timeout period (250ms). If the IO Watchdog is not fed within the timeout period or has expired, the VMXErrorCode will be returned.
◆ SetStatus()
| bool IOWatchdogROS::SetStatus |
( |
std_srvs::SetBool::Request & |
req, |
|
|
std_srvs::SetBool::Response & |
res |
|
) |
| |
Provides the ROS service to enable or disable the IO Watchdog when this service is called on the io_watchdog/status server.
- Parameters
-
| req | SetBool request service type defined in the ROS srv files. |
| res | SetBool response service type defined in the ROS srv files. |
- Returns
- TRUE if the IO Watchdog status is successfully set to enabled or disabled, with an accompanying message.
The documentation for this class was generated from the following files:
- C:/Users/adeya/CLionProjects/ros-dev/vmxpi_ros_io/include/IOwd_ros.h
- C:/Users/adeya/CLionProjects/ros-dev/vmxpi_ros_io/src/IOwd_ros.cpp