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

#include <Servo_ros.h>

Inheritance diagram for ServoROS:
Utils

Public Member Functions

 ServoROS (ros::NodeHandle *nh, VMXPi *vmx, uint8_t channel)
 Constructs the ServoROS object on a specified channel index. More...
 
 ~ServoROS ()
 Destructor for the ServoROS object. More...
 
bool SetAngle (vmxpi_ros::Float::Request &req, vmxpi_ros::Float::Response &res)
 Converts user input of degrees into a value readable by the HAL. More...
 
double GetAngle () const
 Returns the current servo angle. More...
 
double GetMinAngle () const
 Returns the minimum angle of the servo, which is -150deg. More...
 
double GetMaxAngle () const
 Returns the maximum angle of the servo, which is 150deg. More...
 
void Run_t ()
 Provides a method to call the various Services and Publishers of the ServoROS 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

◆ ServoROS()

ServoROS::ServoROS ( ros::NodeHandle *  nh,
VMXPi *  vmx,
uint8_t  channel 
)

Constructs the ServoROS object on a specified channel index.

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.
channelParameter to specify the channel index.

◆ ~ServoROS()

ServoROS::~ServoROS ( )

Destructor for the ServoROS object.

Member Function Documentation

◆ GetAngle()

double ServoROS::GetAngle ( ) const

Returns the current servo angle.

Returns
The current angle of the servo.

◆ GetMaxAngle()

double ServoROS::GetMaxAngle ( ) const

Returns the maximum angle of the servo, which is 150deg.

Returns
The maximum servo angle.

◆ GetMinAngle()

double ServoROS::GetMinAngle ( ) const

Returns the minimum angle of the servo, which is -150deg.

Returns
The minimum servo angle.

◆ Run_t()

void ServoROS::Run_t ( )

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

◆ SetAngle()

bool ServoROS::SetAngle ( vmxpi_ros::Float::Request &  req,
vmxpi_ros::Float::Response &  res 
)

Converts user input of degrees into a value readable by the HAL.

NOTE: The output range is clamped to -150deg - 150deg.

Parameters
reqFloat request service type defined in the Float.srv file.
resFloat response service type defined in the Float.srv file.
Returns
TRUE when the angle of the servo is set. The error code is returned if the VMX PWM Generator Resource's Duty Cycle is not set.

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