Studica - Roscpp Documentation
VMX-pi ROS Library
CobraROS Class Reference

#include <Cobra_ros.h>

Inheritance diagram for CobraROS:
Utils

Public Member Functions

 CobraROS (ros::NodeHandle *nh, VMXPi *vmx)
 Constructs the CobraROS object without specifying a specific device address or reference voltage. The default device address is 0x48 and reference voltage is 5.0F. More...
 
 CobraROS (ros::NodeHandle *nh, VMXPi *vmx, uint8_t deviceAddress_)
 Constructs the CobraROS object without specifying a reference voltage. The default voltage is 5.0F. More...
 
 CobraROS (ros::NodeHandle *nh, VMXPi *vmx, uint8_t deviceAddress_, float vRef_)
 Constructs the CobraROS object using the specified parameters. More...
 
 ~CobraROS ()
 Destructor for the CobraROS object. More...
 
bool IsConnected ()
 Check if the cobra is connected. More...
 
int GetRawValue (uint8_t channel)
 Returns the raw value from the cobra. More...
 
float GetVoltage (uint8_t channel)
 Returns the processed voltage value from the cobra. More...
 
void Run_t ()
 Provides a method to call the various Publishers of the CobraROS library advertising sensor data to the ROS Master node. More...
 
- Public Member Functions inherited from Utils
void DisplayVMXError (VMXErrorCode vmxerr)
 Displays the VMXError. More...
 

Constructor & Destructor Documentation

◆ CobraROS() [1/3]

CobraROS::CobraROS ( ros::NodeHandle *  nh,
VMXPi *  vmx 
)

Constructs the CobraROS object without specifying a specific device address or reference voltage. The default device address is 0x48 and reference voltage is 5.0F.

Parameters
nhInternal reference to the ROS node that the program will use to interact with the ROS system.
vmxVMX-pi parameter used to initialize the VMX-pi HAL.

◆ CobraROS() [2/3]

CobraROS::CobraROS ( ros::NodeHandle *  nh,
VMXPi *  vmx,
uint8_t  deviceAddress_ 
)

Constructs the CobraROS object without specifying a reference voltage. The default voltage is 5.0F.

Parameters
nhInternal reference to the ROS node that the program will use to interact with the ROS system.
vmxVMX-pi parameter used to initialize the VMX-pi HAL.
deviceAddress_Parameter to specify the address of the device.

◆ CobraROS() [3/3]

CobraROS::CobraROS ( ros::NodeHandle *  nh,
VMXPi *  vmx,
uint8_t  deviceAddress_,
float  vRef_ 
)

Constructs the CobraROS object using the specified parameters.

Parameters
nhInternal reference to the ROS node that the program will use to interact with the ROS system.
vmxVMX-pi parameter used to initialize the VMX-pi HAL.
deviceAddress_Parameter to specify the address of the device.
vRef_Parameter to specify the reference voltage of the device.

◆ ~CobraROS()

CobraROS::~CobraROS ( )

Destructor for the CobraROS object.

Member Function Documentation

◆ GetRawValue()

int CobraROS::GetRawValue ( uint8_t  channel)

Returns the raw value from the cobra.

Parameters
channelThe requested cobra channel from 0-3.
Returns
The raw value from the cobra.

◆ GetVoltage()

float CobraROS::GetVoltage ( uint8_t  channel)

Returns the processed voltage value from the cobra.

Parameters
channelThe requested cobra channel from 0-3.
Returns
The processed voltage value from the cobra.

◆ IsConnected()

bool CobraROS::IsConnected ( )

Check if the cobra is connected.

Returns
TRUE if the cobra is connected, otherwise the error code will be displayed and the function will return FALSE.

◆ Run_t()

void CobraROS::Run_t ( )

Provides a method to call the various Publishers of the CobraROS library advertising sensor data to the ROS Master node.


The documentation for this class was generated from the following files: