Studica - Roscpp Documentation
VMX-pi ROS Library
IOwd_ros.h
Go to the documentation of this file.
1#pragma once
2
3#include <ros/ros.h>
4#include "VMXPi.h"
5#include "vmxpi_utils.h"
6#include <unistd.h>
7#include <sys/syscall.h>
8#include <std_srvs/SetBool.h>
9
10class IOWatchdogROS : public Utils {
11 private:
12 VMXIO *io; // IO class of the VMXPi
13 bool status;
14 std::thread runth;
15
16 // service to enable the IO Watchdog loop
17 ros::ServiceServer toggleio;
18
19 public:
29 IOWatchdogROS(ros::NodeHandle *nh, VMXPi *vmx);
30
36
49 bool SetStatus(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res);
50
55 void Run_t();
56
61 void Disable();
62};
Definition: IOwd_ros.h:10
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_w...
Definition: IOwd_ros.cpp:22
void Disable()
Disables all IO Watchdog managed outputs and displays the error code via the pointer to the VMXErrorC...
Definition: IOwd_ros.cpp:32
void Run_t()
Provides a method to regularly "feed" the IO Watchdog while it is enabled before the watchdog timeout...
Definition: IOwd_ros.cpp:38
~IOWatchdogROS()
Destructor for the IOWatchdogROS object.
Definition: IOwd_ros.cpp:18
IOWatchdogROS(ros::NodeHandle *nh, VMXPi *vmx)
Constructs the IOWatchdogROS object.
Definition: IOwd_ros.cpp:3
Definition: vmxpi_utils.h:5