8#include <sys/syscall.h>
9#include <std_msgs/Float32.h>
15 VMXResourceHandle digitalio_res_handles[2];
17 uint8_t channel_index_out, channel_index_in;
19 ros::Publisher ultrasonic_cm_pub, ultrasonic_in_pub, ultrasonic_raw_pub;
21 std::thread ultrasonicth;
40 UltrasonicROS(ros::NodeHandle *nh, VMXPi *pi, uint8_t channelout, uint8_t channelin);
Definition: Ultrasonic_ros.h:11
~UltrasonicROS()
Destructor for the UltrasonicROS object.
Definition: Ultrasonic_ros.cpp:45
void Ultrasonic_t()
Initiates a timed ultrasonic pulse on a DigitalIO Resource in Digital Output Mode in 0....
Definition: Ultrasonic_ros.cpp:115
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.
Definition: Ultrasonic_ros.cpp:3
double GetDistanceCM(uint32_t diff)
Converts microsecond distance from GetRawValue() to centimeters.
Definition: Ultrasonic_ros.cpp:50
uint32_t GetRawValue()
Calculates the raw microsecond difference between the time an ultrasonic wave is emitted and received...
Definition: Ultrasonic_ros.cpp:58
double GetDistanceIN(uint32_t diff)
Converts microsecond distance from GetRawValue() to inches.
Definition: Ultrasonic_ros.cpp:54
void Run_t()
Provides a method to call the various Publishers of the UltrasonicROS library, advertising distance d...
Definition: Ultrasonic_ros.cpp:85
void Ultrasonic()
Creates a thread to continuously emit ultrasonic waves for a default duration of 10µs.
Definition: Ultrasonic_ros.cpp:111
Definition: vmxpi_utils.h:5