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

#include <Ultrasonic_ros.h>

Inheritance diagram for UltrasonicROS:
Utils

Public Member Functions

 UltrasonicROS (ros::NodeHandle *nh, VMXPi *pi, uint8_t channelout, uint8_t channelin)
 Constructs the UltrasonicROS object without specifying the digital input and output channel indexes. More...
 
 ~UltrasonicROS ()
 Destructor for the UltrasonicROS object. More...
 
double GetDistanceCM (uint32_t diff)
 Converts microsecond distance from GetRawValue() to centimeters. More...
 
double GetDistanceIN (uint32_t diff)
 Converts microsecond distance from GetRawValue() to inches. More...
 
uint32_t GetRawValue ()
 Calculates the raw 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. More...
 
void Ultrasonic ()
 Creates a thread to continuously emit ultrasonic waves for a default duration of 10µs. More...
 
void Ultrasonic_t ()
 Initiates a timed ultrasonic pulse on a DigitalIO Resource in Digital Output Mode in 0.1 second intervals. More...
 
void Run_t ()
 Provides a method to call the various Publishers of the UltrasonicROS library, advertising distance data in microseconds, 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

◆ UltrasonicROS()

UltrasonicROS::UltrasonicROS ( ros::NodeHandle *  nh,
VMXPi *  pi,
uint8_t  channelout,
uint8_t  channelin 
)

Constructs the UltrasonicROS object without specifying the digital input and output channel indexes.

NOTE: The valid digital pairs for Trigger and Echo pins are (Trigger, Echo): (0,1), (2,3), (4,5), (6,7), (8, 9), (10,11).

Parameters
nhInternal reference to the ROS node that the program will use to interact with the ROS system.
piVMX-pi parameter used to initialize the VMX-pi HAL.
channeloutOutput channel index.
channelinInput channel index.

◆ ~UltrasonicROS()

UltrasonicROS::~UltrasonicROS ( )

Destructor for the UltrasonicROS object.

Member Function Documentation

◆ GetDistanceCM()

double UltrasonicROS::GetDistanceCM ( uint32_t  diff)

Converts microsecond distance from GetRawValue() to centimeters.

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.

◆ GetDistanceIN()

double UltrasonicROS::GetDistanceIN ( uint32_t  diff)

Converts microsecond distance from GetRawValue() to inches.

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.

◆ GetRawValue()

uint32_t UltrasonicROS::GetRawValue ( )

Calculates the raw 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 microseconds.

◆ Run_t()

void UltrasonicROS::Run_t ( )

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

NOTE: Because the Trigger and Echo pins can vary, the topics are: "channel/input-channel/ultrasonic/dist/inch", "channel/input-channel/ultrasonic/dist/cm", "channel/input-channel/ultrasonic/dist/raw".

◆ Ultrasonic()

void UltrasonicROS::Ultrasonic ( )

Creates a thread to continuously emit ultrasonic waves for a default duration of 10µs.

◆ Ultrasonic_t()

void UltrasonicROS::Ultrasonic_t ( )

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


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