|
Studica - Roscpp Documentation
VMX-pi ROS Library
|
#include <Ultrasonic_ros.h>
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... | |
| 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).
| nh | Internal reference to the ROS node that the program will use to interact with the ROS system. |
| pi | VMX-pi parameter used to initialize the VMX-pi HAL. |
| channelout | Output channel index. |
| channelin | Input channel index. |
| UltrasonicROS::~UltrasonicROS | ( | ) |
Destructor for the UltrasonicROS object.
| double UltrasonicROS::GetDistanceCM | ( | uint32_t | diff | ) |
Converts microsecond distance from GetRawValue() to centimeters.
| diff | 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. |
| double UltrasonicROS::GetDistanceIN | ( | uint32_t | diff | ) |
Converts microsecond distance from GetRawValue() to inches.
| diff | 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. |
| 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.
| 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".
| void UltrasonicROS::Ultrasonic | ( | ) |
Creates a thread to continuously emit ultrasonic waves for a default duration of 10µs.
| void UltrasonicROS::Ultrasonic_t | ( | ) |
Initiates a timed ultrasonic pulse on a DigitalIO Resource in Digital Output Mode in 0.1 second intervals.