Studica - Roscpp Documentation
VMX-pi ROS Library
DI_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 <vmxpi_ros/FloatRes.h>
7
8#include <std_msgs/Float32.h>
9
10
11class DigitalInputROS : public Utils {
12 private:
13 VMXIO *io;
14 VMXTime *time;
15 uint8_t channel_index;
16 VMXResourceHandle digitalin_res_handle;
17
18
19 ros::Publisher di_cm_pub, di_in_pub;
20
21 std::thread runth;
22
23 uint32_t GetRawValue();
24 public:
37 DigitalInputROS(ros::NodeHandle *nh, VMXPi *vmx, uint8_t channel);
38
44
52 bool Get();
53
67 double GetCentimeters(uint32_t diff);
68
82 double GetInches(uint32_t diff);
83
88 void Run_t();
89};
Definition: DI_ros.h:11
DigitalInputROS(ros::NodeHandle *nh, VMXPi *vmx, uint8_t channel)
Constructs the DigitalInputROS object on a specified input channel index.
Definition: DI_ros.cpp:3
double GetInches(uint32_t diff)
Converts microsecond distance from GetRawValue() to inches.
Definition: DI_ros.cpp:47
void Run_t()
Provides a method to call the various Publishers of the DigitalInputROS library, advertising distance...
Definition: DI_ros.cpp:78
double GetCentimeters(uint32_t diff)
Converts microsecond distance from GetRawValue() to centimeters.
Definition: DI_ros.cpp:43
bool Get()
Check the current signal state from a VMX DigitalIO Resource.
Definition: DI_ros.cpp:30
~DigitalInputROS()
Destructor for the DigitalInputROS object.
Definition: DI_ros.cpp:26
Definition: vmxpi_utils.h:5