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

#include <Sharp_ros.h>

Inheritance diagram for SharpROS:
Utils

Public Member Functions

 SharpROS (ros::NodeHandle *nh, VMXPi *vmx)
 Constructs the SharpROS object without specifying the analog channel. The default channel input is set to the first analog channel. More...
 
 SharpROS (ros::NodeHandle *nh, VMXPi *vmx, uint8_t channel)
 Constructs the SharpROS object using the specified parameters. More...
 
 ~SharpROS ()
 Destructor for the SharpROS object. More...
 
double GetIRDistance ()
 Accesses the average voltage data and converts this into a distance output in cm. More...
 
double GetRawVoltage ()
 Returns the current averaged voltage value (in Volts) from the VMX Analog Accumulator Resource. More...
 
void Run_t ()
 Provides a method to call the various Publishers of the SharpROS library advertising sensor data to the ROS Master node. More...
 
- Public Member Functions inherited from Utils
void DisplayVMXError (VMXErrorCode vmxerr)
 Displays the VMXError. More...
 

Constructor & Destructor Documentation

◆ SharpROS() [1/2]

SharpROS::SharpROS ( ros::NodeHandle *  nh,
VMXPi *  vmx 
)

Constructs the SharpROS object without specifying the analog channel. The default channel input is set to the first analog channel.

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.

◆ SharpROS() [2/2]

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

Constructs the SharpROS object using the specified parameters.

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 analog input channels.

NOTE: The valid analog channels range from 22-25.

◆ ~SharpROS()

SharpROS::~SharpROS ( )

Destructor for the SharpROS object.

Member Function Documentation

◆ GetIRDistance()

double SharpROS::GetIRDistance ( )

Accesses the average voltage data and converts this into a distance output in cm.

Returns
Outputs the range in cm.

◆ GetRawVoltage()

double SharpROS::GetRawVoltage ( )

Returns the current averaged voltage value (in Volts) from the VMX Analog Accumulator Resource.

Returns
Average raw voltage readings.

◆ Run_t()

void SharpROS::Run_t ( )

Provides a method to call the various Publishers of the SharpROS library advertising sensor data to the ROS Master node.


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