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

#include <DO_ros.h>

Inheritance diagram for DigitalOutputROS:
Utils

Public Member Functions

 DigitalOutputROS (ros::NodeHandle *nh, VMXPi *vmx, uint8_t channel)
 Constructs the DigitalOutputROS object on a specified output channel index. More...
 
bool Ping (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 Initiates a timed ultrasonic pulse on a DigitalIO Resource in Digital Output Mode in 0.1 second intervals. More...
 
bool SetDuration (vmxpi_ros::Int::Request &req, vmxpi_ros::Int::Response &res)
 Sets the duration of the ping signal. More...
 
- Public Member Functions inherited from Utils
void DisplayVMXError (VMXErrorCode vmxerr)
 Displays the VMXError. More...
 

Constructor & Destructor Documentation

◆ DigitalOutputROS()

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

Constructs the DigitalOutputROS object on a specified output 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 output channel index.

Member Function Documentation

◆ Ping()

bool DigitalOutputROS::Ping ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)

Initiates a timed ultrasonic pulse on a DigitalIO Resource in Digital Output Mode in 0.1 second intervals.

Parameters
reqEmpty request type defined in the ROS srv files.
resEmpty response type defined in the ROS srv files.
Returns
TRUE when an ultrasonic ping signal is sent in 100ms intervals, otherwise the error code is returned if the DIO Pulse was not initiated.

◆ SetDuration()

bool DigitalOutputROS::SetDuration ( vmxpi_ros::Int::Request &  req,
vmxpi_ros::Int::Response &  res 
)

Sets the duration of the ping signal.

Parameters
reqInteger request service type defined in the Int.srv file.
resInteger response service type defined in the Int.srv file.
Returns
TRUE when the duration of the ping signal is set.

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