10#include <std_msgs/Int16.h>
11#include <std_msgs/Float32.h>
12#include <sys/syscall.h>
15#define POINTER_CONVERT 0X0000
16#define POINTER_CONFIG 0x0001
17#define POINTER_LOWTHRESH 0x0002
18#define POINTER_HITHRESH 0x0003
19#define CONFIG_OS_NO 0x8000
20#define CONFIG_OS_SINGLE 0x8000
21#define CONFIG_OS_READY 0x8000
22#define CONFIG_OS_NOTREADY 0x8000
23#define CONFIG_MODE_CONT 0x0000
24#define CONFIG_MODE_SINGLE 0x0100
25#define CONFIG_MUX_SINGLE_0 0x4000
26#define CONFIG_MUX_SINGLE_1 0x5000
27#define CONFIG_MUX_SINGLE_2 0x6000
28#define CONFIG_MUX_SINGLE_3 0x7000
29#define CONFIG_MUX_DIFF_PO_N1 0x0000
30#define CONFIG_MUX_DIFF_PO_N3 0x1000
31#define CONFIG_MUX_DIFF_P1_N3 0x2000
32#define CONFIG_MUX_DIFF_P2_N3 0x3000
33#define CONFIG_RATE_128HZ 0x0000
34#define CONFIG_RATE_250HZ 0x0020
35#define CONFIG_RATE_490HZ 0x0040
36#define CONFIG_RATE_920HZ 0x0060
37#define CONFIG_RATE_1600HZ 0x0080
38#define CONFIG_RATE_2400HZ 0x00A0
39#define CONFIG_RATE_3300HZ 0x00C0
40#define CONFIG_PGA_MASK 0x0E00
41#define CONFIG_PGA_TWOTHIRDS 0x0000
42#define CONFIG_PGA_1 0x0200
43#define CONFIG_PGA_2 0x0400
44#define CONFIG_PGA_4 0x0600
45#define CONFIG_PGA_8 0x0800
46#define CONFIG_PGA_16 0x0A00
47#define CONFIG_CMODE_TRAD 0x0000
48#define CONFIG_CMODE_WINDOW 0x0010
49#define CONFIG_CPOL_ACTVLOW 0x0000
50#define CONFIG_CPOL_ACTVHI 0x0008
51#define CONFIG_CLAT_NOLAT 0x0000
52#define CONFIG_CLAT_LATCH 0x0004
53#define CONFIG_CQUE_1CONV 0x0000
54#define CONFIG_CQUE_2CONV 0x0001
55#define CONFIG_CQUE_4CONV 0x0002
56#define CONFIG_CQUE_NONE 0x0003
61 VMXResourceHandle i2c_res_handle;
64 uint8_t deviceAddress;
66 ros::Publisher c0_raw_pub, c0_v_pub,
71 int GetSingle(uint8_t channel);
85 CobraROS(ros::NodeHandle *nh, VMXPi *vmx);
98 CobraROS(ros::NodeHandle *nh, VMXPi *vmx, uint8_t deviceAddress_);
112 CobraROS(ros::NodeHandle *nh, VMXPi *vmx, uint8_t deviceAddress_,
float vRef_);
Definition: Cobra_ros.h:58
CobraROS(ros::NodeHandle *nh, VMXPi *vmx)
Constructs the CobraROS object without specifying a specific device address or reference voltage....
Definition: Cobra_ros.cpp:3
float GetVoltage(uint8_t channel)
Returns the processed voltage value from the cobra.
Definition: Cobra_ros.cpp:139
bool IsConnected()
Check if the cobra is connected.
Definition: Cobra_ros.cpp:123
void Run_t()
Provides a method to call the various Publishers of the CobraROS library advertising sensor data to t...
Definition: Cobra_ros.cpp:189
int GetRawValue(uint8_t channel)
Returns the raw value from the cobra.
Definition: Cobra_ros.cpp:135
~CobraROS()
Destructor for the CobraROS object.
Definition: Cobra_ros.cpp:115
Definition: vmxpi_utils.h:5