|
Studica - Roscpp Documentation
VMX-pi ROS Library
|
#include <Sharp_ros.h>
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... | |
| 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.
| nh | Internal reference to the ROS node that the program will use to interact with the ROS system. |
| vmx | VMX-pi parameter used to initialize the VMX-pi HAL. |
| SharpROS::SharpROS | ( | ros::NodeHandle * | nh, |
| VMXPi * | vmx, | ||
| uint8_t | channel | ||
| ) |
Constructs the SharpROS object using the specified parameters.
| nh | Internal reference to the ROS node that the program will use to interact with the ROS system. |
| vmx | VMX-pi parameter used to initialize the VMX-pi HAL. |
| channel | Parameter to specify the analog input channels. |
NOTE: The valid analog channels range from 22-25.
| SharpROS::~SharpROS | ( | ) |
Destructor for the SharpROS object.
| double SharpROS::GetIRDistance | ( | ) |
Accesses the average voltage data and converts this into a distance output in cm.
| double SharpROS::GetRawVoltage | ( | ) |
Returns the current averaged voltage value (in Volts) from the VMX Analog Accumulator Resource.
| void SharpROS::Run_t | ( | ) |
Provides a method to call the various Publishers of the SharpROS library advertising sensor data to the ROS Master node.