Studica - Roscpp Documentation
VMX-pi ROS Library
Ultrasonic_ros.h
Go to the documentation of this file.
1#pragma once
2
3#include <ros/ros.h>
4#include "VMXPi.h"
5#include "vmxpi_utils.h"
6#include <chrono>
7#include <inttypes.h>
8#include <sys/syscall.h>
9#include <std_msgs/Float32.h>
10
11class UltrasonicROS : public Utils {
12 private:
13 VMXIO *io; // IO class of VMXPi
14 VMXTime *time; // Time class of VMXPi
15 VMXResourceHandle digitalio_res_handles[2];
16
17 uint8_t channel_index_out, channel_index_in; // channel indexes for DI and DO
18
19 ros::Publisher ultrasonic_cm_pub, ultrasonic_in_pub, ultrasonic_raw_pub;
20
21 std::thread ultrasonicth;
22 std::thread runth;
23
24 public:
40 UltrasonicROS(ros::NodeHandle *nh, VMXPi *pi, uint8_t channelout, uint8_t channelin);
41
47
59 double GetDistanceCM(uint32_t diff); // get distance in cm
60
72 double GetDistanceIN(uint32_t diff); // get distance in inches
73
82 uint32_t GetRawValue(); // get raw value
83
88 void Ultrasonic();
89
94 void Ultrasonic_t();
95
102 void Run_t();
103
104};
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