6#include <std_msgs/Float32.h>
9#include <sys/syscall.h>
14 VMXResourceHandle accumulator_res_handle;
15 uint8_t analog_in_chan_index;
17 ros::Publisher sharp_dist_pub, raw_voltage_pub;
33 SharpROS(ros::NodeHandle *nh, VMXPi *vmx);
49 SharpROS(ros::NodeHandle *nh, VMXPi *vmx, uint8_t channel);
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