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

#include <TitanDriver_ros_wrapper.h>

Public Member Functions

 TitanDriverROSWrapper (ros::NodeHandle *nh, VMXPi *vmx)
 Constructs the TitanDriverROSWrapper object using the specified parameters. More...
 
 ~TitanDriverROSWrapper ()
 Destructor for the TitanDriverROSWrapper object. More...
 
bool SetMotorSpeed (vmxpi_ros::MotorSpeed::Request &req, vmxpi_ros::MotorSpeed::Response &res)
 Provides a ROS service to set the specified motor's speed. More...
 
bool callbackStop (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 Provides a ROS service o stop all motors. More...
 
void StopMotor (int motor)
 Method to stop a specified motor. More...
 
void StopAllMotors ()
 Method to stop all motors. More...
 
bool Enable (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 Enables Titan by sending an enabled flag through the object's run loop. More...
 
bool Disable (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 Disables Titan by sending a disabled flag through the object's run loop. More...
 
bool ResetEncoder (vmxpi_ros::Int::Request &req, vmxpi_ros::Int::Response &res)
 Resets encoder count for specified encoder. More...
 
bool ResetAllEncoders (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 Resets encoder counts for all motors. More...
 
bool SetMotorStopMode (vmxpi_ros::StopMode::Request &req, vmxpi_ros::StopMode::Response &res)
 Sets the stop mode on the specified motor (0 = coast, 1 = break). More...
 
void PubUniqueID ()
 Publishes Titan's unique ID to /titan/unique_id. More...
 
void PubTitanInfo ()
 Publishes Titan's info (version, hardware) to /titan/info. More...
 
void PubMotorSpeed (uint8_t motor)
 Publishes motor speed (0 - 1.0) to titan/motorX/speed. More...
 
void PubMotorFreq ()
 Publishes motor frequencies to /titan/motorX/freq. More...
 
void GetCountRPM ()
 Returns the encoder count + RPM packet for each encoder. More...
 
void PubEncoderCount (int8_t encoder)
 Publishes the encoder counts to /titan/encoderX/count. More...
 
void PubEncoderDist (int8_t encoder)
 Publishes encoder distances to /titan/encoderX/distance. More...
 
void PubRPM (uint8_t motor)
 Publishes the RPM of the specified motor to /titan/motorX/rpm. More...
 
void PubLimitSwitch ()
 Publishes limit switch values to /titan/limit_switch. More...
 
void PubMCUTemp ()
 Publishes MCU (CPU) temp to /titan/mcu_temp. More...
 
void Run1_t ()
 Provides a method to call the first thread of various Publishers of the TitanDriverROSWrapper library advertising sensor data to the ROS Master node. More...
 
void Run2_t ()
 

Constructor & Destructor Documentation

◆ TitanDriverROSWrapper()

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

Constructs the TitanDriverROSWrapper 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.

◆ ~TitanDriverROSWrapper()

TitanDriverROSWrapper::~TitanDriverROSWrapper ( )

Destructor for the TitanDriverROSWrapper object.

Member Function Documentation

◆ callbackStop()

bool TitanDriverROSWrapper::callbackStop ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)

Provides a ROS service o stop all motors.

Parameters
reqTrigger request type defined in the ROS srv files.
resTrigger response type defined in the ROS srv files.
Returns
TRUE when all the motors have been stopped.

◆ Disable()

bool TitanDriverROSWrapper::Disable ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)

Disables Titan by sending a disabled flag through the object's run loop.

Parameters
reqTrigger request type defined in the ROS srv files.
resTrigger response type defined in the ROS srv files.
Returns
TRUE when the enabled flag has been set to false.

◆ Enable()

bool TitanDriverROSWrapper::Enable ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)

Enables Titan by sending an enabled flag through the object's run loop.

Parameters
reqTrigger request type defined in the ROS srv files.
resTrigger response type defined in the ROS srv files.
Returns
TRUE when the enabled flag has been set to true.

◆ GetCountRPM()

void TitanDriverROSWrapper::GetCountRPM ( )

Returns the encoder count + RPM packet for each encoder.

◆ PubEncoderCount()

void TitanDriverROSWrapper::PubEncoderCount ( int8_t  encoder)

Publishes the encoder counts to /titan/encoderX/count.

Parameters
encoderParameter to specify the encoder.

◆ PubEncoderDist()

void TitanDriverROSWrapper::PubEncoderDist ( int8_t  encoder)

Publishes encoder distances to /titan/encoderX/distance.

Parameters
encoderParameter to specify the encoder.

◆ PubLimitSwitch()

void TitanDriverROSWrapper::PubLimitSwitch ( )

Publishes limit switch values to /titan/limit_switch.

Sent as a bool array: {M0 L H, M0 L L, M1 L H, M1 L L, M2 L H, M2 L L, M3 L H, M3 L L}

L = Low limit switch, H = High limit switch

◆ PubMCUTemp()

void TitanDriverROSWrapper::PubMCUTemp ( )

Publishes MCU (CPU) temp to /titan/mcu_temp.

◆ PubMotorFreq()

void TitanDriverROSWrapper::PubMotorFreq ( )

Publishes motor frequencies to /titan/motorX/freq.

◆ PubMotorSpeed()

void TitanDriverROSWrapper::PubMotorSpeed ( uint8_t  motor)

Publishes motor speed (0 - 1.0) to titan/motorX/speed.

Parameters
motorParameter to specify the motor.

◆ PubRPM()

void TitanDriverROSWrapper::PubRPM ( uint8_t  motor)

Publishes the RPM of the specified motor to /titan/motorX/rpm.

Parameters
motorParameter to specify the motor.

◆ PubTitanInfo()

void TitanDriverROSWrapper::PubTitanInfo ( )

Publishes Titan's info (version, hardware) to /titan/info.

deviceID: int32 (1-63)

verMaj: int32 (version format is <verMaj>.<verMin>.<verBuild>)

verMin: int32

verBuild: int32

hardware: int32 (1 = Titan Quad, 2 = Titan Small)

hardwareRev: int32

◆ PubUniqueID()

void TitanDriverROSWrapper::PubUniqueID ( )

Publishes Titan's unique ID to /titan/unique_id.

word1: hex value

word2: hex value

word3: hex value

Format: <word1>.<word2>.<word3>

◆ ResetAllEncoders()

bool TitanDriverROSWrapper::ResetAllEncoders ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)

Resets encoder counts for all motors.

Parameters
reqTrigger request type defined in the ROS srv files.
resTrigger response type defined in the ROS srv files.
Returns
TRUE when the encoder counts for all the motors have been reset.

◆ ResetEncoder()

bool TitanDriverROSWrapper::ResetEncoder ( vmxpi_ros::Int::Request &  req,
vmxpi_ros::Int::Response &  res 
)

Resets encoder count for specified encoder.

Parameters
reqInt request type defined in the Int.srv file.
resInt response type defined in the Int.srv file.
Returns
TRUE when the encoder count of the specified motor has been reset.

◆ Run1_t()

void TitanDriverROSWrapper::Run1_t ( )

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

◆ Run2_t()

void TitanDriverROSWrapper::Run2_t ( )

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

◆ SetMotorSpeed()

bool TitanDriverROSWrapper::SetMotorSpeed ( vmxpi_ros::MotorSpeed::Request &  req,
vmxpi_ros::MotorSpeed::Response &  res 
)

Provides a ROS service to set the specified motor's speed.

NOTE: Valid values range from 0 - 1.0.

Parameters
reqRequest service type defined in the MotorSpeed.srv file.
resResponse service type defined in the MotorSpeed.srv file.
Returns
TRUE after setting the speed of a specific motor.

◆ SetMotorStopMode()

bool TitanDriverROSWrapper::SetMotorStopMode ( vmxpi_ros::StopMode::Request &  req,
vmxpi_ros::StopMode::Response &  res 
)

Sets the stop mode on the specified motor (0 = coast, 1 = break).

Parameters
reqStopMode request service type defined in the StopMode.srv file.
resStopMode response service type defined in the StopMode srv file.
Returns
TRUE when the stop mode of the specified motor has been set.

◆ StopAllMotors()

void TitanDriverROSWrapper::StopAllMotors ( )

Method to stop all motors.

◆ StopMotor()

void TitanDriverROSWrapper::StopMotor ( int  motor)

Method to stop a specified motor.

Parameters
motorThe requested motor.

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