|
Studica - Roscpp Documentation
VMX-pi ROS Library
|
#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 () |
| TitanDriverROSWrapper::TitanDriverROSWrapper | ( | ros::NodeHandle * | nh, |
| VMXPi * | vmx | ||
| ) |
Constructs the TitanDriverROSWrapper object using the specified parameters.
| nh | Internal reference to the ROS node that the program will use to interact with the ROS system. |
| vmx | VMX-pi parameter used to initialize the VMX-pi HAL. |
| TitanDriverROSWrapper::~TitanDriverROSWrapper | ( | ) |
Destructor for the TitanDriverROSWrapper object.
| bool TitanDriverROSWrapper::callbackStop | ( | std_srvs::Trigger::Request & | req, |
| std_srvs::Trigger::Response & | res | ||
| ) |
Provides a ROS service o stop all motors.
| req | Trigger request type defined in the ROS srv files. |
| res | Trigger response type defined in the ROS srv files. |
| 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.
| req | Trigger request type defined in the ROS srv files. |
| res | Trigger response type defined in the ROS srv files. |
| 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.
| req | Trigger request type defined in the ROS srv files. |
| res | Trigger response type defined in the ROS srv files. |
| void TitanDriverROSWrapper::GetCountRPM | ( | ) |
Returns the encoder count + RPM packet for each encoder.
| void TitanDriverROSWrapper::PubEncoderCount | ( | int8_t | encoder | ) |
Publishes the encoder counts to /titan/encoderX/count.
| encoder | Parameter to specify the encoder. |
| void TitanDriverROSWrapper::PubEncoderDist | ( | int8_t | encoder | ) |
Publishes encoder distances to /titan/encoderX/distance.
| encoder | Parameter to specify the encoder. |
| 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
| void TitanDriverROSWrapper::PubMCUTemp | ( | ) |
Publishes MCU (CPU) temp to /titan/mcu_temp.
| void TitanDriverROSWrapper::PubMotorFreq | ( | ) |
Publishes motor frequencies to /titan/motorX/freq.
| void TitanDriverROSWrapper::PubMotorSpeed | ( | uint8_t | motor | ) |
Publishes motor speed (0 - 1.0) to titan/motorX/speed.
| motor | Parameter to specify the motor. |
| void TitanDriverROSWrapper::PubRPM | ( | uint8_t | motor | ) |
Publishes the RPM of the specified motor to /titan/motorX/rpm.
| motor | Parameter to specify the motor. |
| 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
| 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>
| bool TitanDriverROSWrapper::ResetAllEncoders | ( | std_srvs::Trigger::Request & | req, |
| std_srvs::Trigger::Response & | res | ||
| ) |
Resets encoder counts for all motors.
| req | Trigger request type defined in the ROS srv files. |
| res | Trigger response type defined in the ROS srv files. |
| bool TitanDriverROSWrapper::ResetEncoder | ( | vmxpi_ros::Int::Request & | req, |
| vmxpi_ros::Int::Response & | res | ||
| ) |
Resets encoder count for specified encoder.
| req | Int request type defined in the Int.srv file. |
| res | Int response type defined in the Int.srv file. |
| 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.
| 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.
| 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.
| req | Request service type defined in the MotorSpeed.srv file. |
| res | Response service type defined in the MotorSpeed.srv file. |
| 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).
| req | StopMode request service type defined in the StopMode.srv file. |
| res | StopMode response service type defined in the StopMode srv file. |
| void TitanDriverROSWrapper::StopAllMotors | ( | ) |
Method to stop all motors.
| void TitanDriverROSWrapper::StopMotor | ( | int | motor | ) |
Method to stop a specified motor.
| motor | The requested motor. |