Studica - Roscpp Documentation
VMX-pi ROS Library
DigitalInputROS Class Reference

#include <DI_ros.h>

Inheritance diagram for DigitalInputROS:
Utils

Public Member Functions

 DigitalInputROS (ros::NodeHandle *nh, VMXPi *vmx, uint8_t channel)
 Constructs the DigitalInputROS object on a specified input channel index. More...
 
 ~DigitalInputROS ()
 Destructor for the DigitalInputROS object. More...
 
bool Get ()
 Check the current signal state from a VMX DigitalIO Resource. More...
 
double GetCentimeters (uint32_t diff)
 Converts microsecond distance from GetRawValue() to centimeters. More...
 
double GetInches (uint32_t diff)
 Converts microsecond distance from GetRawValue() to inches. More...
 
void Run_t ()
 Provides a method to call the various Publishers of the DigitalInputROS library, advertising distance data in inches and centimeters to the ROS Master node. More...
 
- Public Member Functions inherited from Utils
void DisplayVMXError (VMXErrorCode vmxerr)
 Displays the VMXError. More...
 

Constructor & Destructor Documentation

◆ DigitalInputROS()

DigitalInputROS::DigitalInputROS ( ros::NodeHandle *  nh,
VMXPi *  vmx,
uint8_t  channel 
)

Constructs the DigitalInputROS object on a specified input channel index.

Parameters
nhInternal reference to the ROS node that the program will use to interact with the ROS system.
vmxVMX-pi parameter used to initialize the VMX-pi HAL.
channelParameter to specify the input channel index.

◆ ~DigitalInputROS()

DigitalInputROS::~DigitalInputROS ( )

Destructor for the DigitalInputROS object.

Member Function Documentation

◆ Get()

bool DigitalInputROS::Get ( )

Check the current signal state from a VMX DigitalIO Resource.

Returns
TRUE if a valid DigitalIO signal state was returned, otherwise the error code is returned if FALSE.

◆ GetCentimeters()

double DigitalInputROS::GetCentimeters ( uint32_t  diff)

Converts microsecond distance from GetRawValue() to centimeters.

NOTE: Because the Ultrasonic class is inherently a DIO class since the pins are connected, this method exists for both the UltrasonicROS and DigitalInputROS classes.

Parameters
diffRaw microsecond difference between the time an ultrasonic wave is emitted and received as the wave is reflected back from the target. This directly corresponds to the distance (in microseconds) measured from the sensor to the target.
Returns
Distance in centimeters.

◆ GetInches()

double DigitalInputROS::GetInches ( uint32_t  diff)

Converts microsecond distance from GetRawValue() to inches.

NOTE: Because the Ultrasonic class is inherently a DIO class since the pins are connected, this method exists for both the UltrasonicROS and DigitalInputROS classes.

Parameters
diffRaw microsecond difference between the time an ultrasonic wave is emitted and received as the wave is reflected back from the target. This directly corresponds to the distance (in microseconds) measured from the sensor to the target.
Returns
Distance in inches.

◆ Run_t()

void DigitalInputROS::Run_t ( )

Provides a method to call the various Publishers of the DigitalInputROS library, advertising distance data in inches and centimeters to the ROS Master node.


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