Studica - Roscpp Documentation
VMX-pi ROS Library
Sharp_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 <std_msgs/Float32.h>
7#include <thread>
8#include <unistd.h>
9#include <sys/syscall.h>
10
11class SharpROS : public Utils {
12 private:
13 VMXIO *io; // IO class of VMXPi
14 VMXResourceHandle accumulator_res_handle;
15 uint8_t analog_in_chan_index;
16
17 ros::Publisher sharp_dist_pub, raw_voltage_pub;
18
19 std::thread runth;
20
21
22 public:
32 // first channel input
33 SharpROS(ros::NodeHandle *nh, VMXPi *vmx);
34
48 // specify channel input
49 SharpROS(ros::NodeHandle *nh, VMXPi *vmx, uint8_t channel);
50
55 ~SharpROS();
56
64 double GetIRDistance(); // get distance in cm
65
73 double GetRawVoltage(); // get raw voltage
74
79 void Run_t();
80};
Definition: Sharp_ros.h:11
void Run_t()
Provides a method to call the various Publishers of the SharpROS library advertising sensor data to t...
Definition: Sharp_ros.cpp:83
~SharpROS()
Destructor for the SharpROS object.
Definition: Sharp_ros.cpp:65
SharpROS(ros::NodeHandle *nh, VMXPi *vmx)
Constructs the SharpROS object without specifying the analog channel. The default channel input is se...
Definition: Sharp_ros.cpp:3
double GetRawVoltage()
Returns the current averaged voltage value (in Volts) from the VMX Analog Accumulator Resource.
Definition: Sharp_ros.cpp:73
double GetIRDistance()
Accesses the average voltage data and converts this into a distance output in cm.
Definition: Sharp_ros.cpp:69
Definition: vmxpi_utils.h:5