Studica - Roscpp Documentation
VMX-pi ROS Library
TitanDriver_ros_wrapper.h
Go to the documentation of this file.
1#pragma once
2
3#include <memory>
4#include <ros/ros.h>
5#include <stdint.h>
6#include <thread>
7#include "TitanDriver_ros.h"
8#include <unistd.h>
9#include <sys/syscall.h>
10
11#include <std_srvs/Trigger.h>
12#include <std_msgs/Float32.h>
13#include <std_msgs/Int16.h>
14#include <std_msgs/Int32.h>
15#include <std_msgs/UInt16.h>
16#include <vmxpi_ros/TitanInfo.h>
17#include <vmxpi_ros/UniqueID.h>
18#include <vmxpi_ros/Int.h>
19#include <vmxpi_ros/StopMode.h>
20#include <vmxpi_ros/LimitSwitch.h>
21#include <vmxpi_ros/MotorSpeed.h>
22
24{
25 private:
26 std::unique_ptr<TitanDriver> Titan;
27 VMXCAN *can;
28 ros::ServiceServer stop_motor_server, test_server, enable_server, disable_server, reset_server, motor_stop_mode_server,
29 motor_speed;
30 ros::Publisher uniqueid_pub, info_publisher, motor0freq_pub, motor1freq_pub, motor2freq_pub, motor3freq_pub,
31 motor0speed_pub, motor1speed_pub, motor2speed_pub, motor3speed_pub,
32 enc0_pub, enc1_pub, enc2_pub, enc3_pub,
33 encdist0_pub, encdist1_pub, encdist2_pub, encdist3_pub,
34 rpm0_pub, rpm1_pub, rpm2_pub, rpm3_pub,
35 limitswitch_pub, mcutemp_pub;
36
37
38
39 std::thread run1th, run2th;
40 public:
50 TitanDriverROSWrapper(ros::NodeHandle *nh, VMXPi *vmx);
51
57
72 // Sets specified motor's speed, valid values (0 - 1.0)
73 bool SetMotorSpeed(vmxpi_ros::MotorSpeed::Request &req, vmxpi_ros::MotorSpeed::Response &res);
74
87 // Stop all motors when service is called
88 bool callbackStop(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
89
97 // Class function to stop specified motor
98 void StopMotor(int motor);
99
104 // Class function to stop all motors
105 void StopAllMotors();
106
119 // Enables Titan by sending an enabled flag through object's run loop
120 bool Enable(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
121
134 // Disables Titan by sending a disabled flag through object's run loop
135 bool Disable(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
136
149 // Resets specified encoder's count
150 bool ResetEncoder(vmxpi_ros::Int::Request &req, vmxpi_ros::Int::Response &res);
151
164 // Resets all encoder counts
165 bool ResetAllEncoders(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
166
179 /* Sets specified motor's stop mode
180 * mode: (0 = coast, 1 = break) */
181 bool SetMotorStopMode(vmxpi_ros::StopMode::Request &req, vmxpi_ros::StopMode::Response &res);
182
183 // --- Publishers --- //
184
197 void PubUniqueID();
198
215 void PubTitanInfo();
216
224 // Publish motor speeds (0 - 1.0) to /titan/motorX/speed
225 void PubMotorSpeed(uint8_t motor);
226
231 // Publish motor frequencies to /titan/motorX/freq
232 void PubMotorFreq();
233
238 void GetCountRPM();
239
247 // Publish encoder counts to /titan/encoderX/count
248 void PubEncoderCount(int8_t encoder);
249
257 // Publish encoder distances to /titan/encoderX/distance
258 void PubEncoderDist(int8_t encoder);
259
267 // Publish encoder RPM to /titan/motorX/rpm
268 void PubRPM(uint8_t motor);
269
277 void PubLimitSwitch();
278
283 // Publish MCU (CPU) temp to /titan/mcu_temp
284 void PubMCUTemp();
285
290 void Run1_t();
291
295 void Run2_t();
296};
297
298
Definition: TitanDriver_ros_wrapper.h:24
void PubLimitSwitch()
Publishes limit switch values to /titan/limit_switch.
Definition: TitanDriver_ros_wrapper.cpp:197
void PubMotorFreq()
Publishes motor frequencies to /titan/motorX/freq.
Definition: TitanDriver_ros_wrapper.cpp:142
TitanDriverROSWrapper(ros::NodeHandle *nh, VMXPi *vmx)
Constructs the TitanDriverROSWrapper object using the specified parameters.
Definition: TitanDriver_ros_wrapper.cpp:3
~TitanDriverROSWrapper()
Destructor for the TitanDriverROSWrapper object.
Definition: TitanDriver_ros_wrapper.cpp:63
void Run2_t()
Definition: TitanDriver_ros_wrapper.cpp:224
void PubMCUTemp()
Publishes MCU (CPU) temp to /titan/mcu_temp.
Definition: TitanDriver_ros_wrapper.cpp:203
void GetCountRPM()
Returns the encoder count + RPM packet for each encoder.
Definition: TitanDriver_ros_wrapper.cpp:151
void PubUniqueID()
Publishes Titan's unique ID to /titan/unique_id.
Definition: TitanDriver_ros_wrapper.cpp:117
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.
Definition: TitanDriver_ros_wrapper.cpp:85
void StopMotor(int motor)
Method to stop a specified motor.
Definition: TitanDriver_ros_wrapper.cpp:81
void Run1_t()
Provides a method to call the first thread of various Publishers of the TitanDriverROSWrapper library...
Definition: TitanDriver_ros_wrapper.cpp:209
void PubMotorSpeed(uint8_t motor)
Publishes motor speed (0 - 1.0) to titan/motorX/speed.
Definition: TitanDriver_ros_wrapper.cpp:129
bool SetMotorStopMode(vmxpi_ros::StopMode::Request &req, vmxpi_ros::StopMode::Response &res)
Sets the stop mode on the specified motor (0 = coast, 1 = break).
Definition: TitanDriver_ros_wrapper.cpp:112
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.
Definition: TitanDriver_ros_wrapper.cpp:100
void PubRPM(uint8_t motor)
Publishes the RPM of the specified motor to /titan/motorX/rpm.
Definition: TitanDriver_ros_wrapper.cpp:184
bool ResetAllEncoders(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Resets encoder counts for all motors.
Definition: TitanDriver_ros_wrapper.cpp:92
bool callbackStop(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Provides a ROS service o stop all motors.
Definition: TitanDriver_ros_wrapper.cpp:74
bool SetMotorSpeed(vmxpi_ros::MotorSpeed::Request &req, vmxpi_ros::MotorSpeed::Response &res)
Provides a ROS service to set the specified motor's speed.
Definition: TitanDriver_ros_wrapper.cpp:69
void PubEncoderCount(int8_t encoder)
Publishes the encoder counts to /titan/encoderX/count.
Definition: TitanDriver_ros_wrapper.cpp:158
void PubEncoderDist(int8_t encoder)
Publishes encoder distances to /titan/encoderX/distance.
Definition: TitanDriver_ros_wrapper.cpp:171
void PubTitanInfo()
Publishes Titan's info (version, hardware) to /titan/info.
Definition: TitanDriver_ros_wrapper.cpp:123
bool ResetEncoder(vmxpi_ros::Int::Request &req, vmxpi_ros::Int::Response &res)
Resets encoder count for specified encoder.
Definition: TitanDriver_ros_wrapper.cpp:107
void StopAllMotors()
Method to stop all motors.
Definition: TitanDriver_ros_wrapper.cpp:83