Tetrapod Project
motor_interface.h
Go to the documentation of this file.
1 /*******************************************************************/
2 /* AUTHOR: Paal Arthur S. Thorseth */
3 /* ORGN: Dept of Eng Cybernetics, NTNU Trondheim */
4 /* FILE: motor_interface.h */
5 /* DATE: Apr 23, 2021 */
6 /* */
7 /* Copyright (C) 2021 Paal Arthur S. Thorseth, */
8 /* Adrian B. Ghansah */
9 /* */
10 /* This program is free software: you can redistribute it */
11 /* and/or modify it under the terms of the GNU General */
12 /* Public License as published by the Free Software Foundation, */
13 /* either version 3 of the License, or (at your option) any */
14 /* later version. */
15 /* */
16 /* This program is distributed in the hope that it will be useful, */
17 /* but WITHOUT ANY WARRANTY; without even the implied warranty */
18 /* of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. */
19 /* See the GNU General Public License for more details. */
20 /* */
21 /* You should have received a copy of the GNU General Public */
22 /* License along with this program. If not, see */
23 /* <https://www.gnu.org/licenses/>. */
24 /* */
25 /*******************************************************************/
26 
27 #pragma once
28 
29 // ROS
30 #include "ros/ros.h"
31 #include "ros/callback_queue.h"
32 #include "sensor_msgs/JointState.h"
33 #include "std_msgs/Float64.h"
34 #include "std_msgs/Float64MultiArray.h"
35 #include "std_srvs/Empty.h"
36 #include "eigen_conversions/eigen_msg.h"
37 
38 // ROS Package Libraries
40 
41 // Standard library
42 #include <thread>
43 
44 // Eigen
45 #include <Eigen/Core>
46 
49 {
51  private: static constexpr int MAX_NUM_MOTORS_PER_PORT = 6;
52 
54  public: MotorInterface();
55 
58  public: MotorInterface(const int &_num_motors);
59 
61  public: virtual ~MotorInterface();
62 
65  public: void SetJointPositions(const std::vector<double> &_pos);
66 
69  public: void SetJointVelocities(const std::vector<double> &_vel);
70 
73  public: void SetJointTorques(const std::vector<double> &_torque);
74 
77  public: void ProcessSerialMessages();
78 
83  public: void OnJointStateCmdMsg(const sensor_msgs::JointStateConstPtr &_msg);
84 
87  public: void SerialProcessQueueThread();
88 
91  public: void RosProcessQueueThread();
92 
95  public: void RosPublishQueueThread();
96 
102  public: bool Shutdown(const std_srvs::Empty::Request &_req,
103  std_srvs::Empty::Response &_res);
104 
106  protected: void InitRos();
107 
110  protected: void InitRosQueueThreads();
111 
113  private: const int NUM_MOTORS;
114 
116  private: int num_motors_port_1;
117 
119  private: int num_motors_port_2;
120 
123 
126 
128  private: std::unique_ptr<ros::NodeHandle> rosNode;
129 
131  private: sensor_msgs::JointState jointStateMsg;
132 
134  private: ros::ServiceServer shutdownService;
135 
137  private: ros::Subscriber jointStateCmdSub;
138 
140  private: ros::Publisher jointStatePub;
141 
143  private: ros::CallbackQueue rosProcessQueue;
144 
146  private: ros::CallbackQueue rosPublishQueue;
147 
149  private: std::thread serialProcessQueueThread;
150 
152  private: std::thread rosProcessQueueThread;
153 
155  private: std::thread rosPublishQueueThread;
156 };
A class to control and distribute motor position, velocity and torque information.
int num_motors_port_2
The number of motors interfaced by the second Teensy.
void InitRosQueueThreads()
The InitRosQueueThreads function is called to initialize the ROS Publish and Process Queue Threads.
std::thread rosPublishQueueThread
Thread running the rosPublishQueue.
std::thread rosProcessQueueThread
Thread running the rosProcessQueue.
void ProcessSerialMessages()
Checks if there are any incomming messages from the serial ports. If there are new replies these are ...
void RosProcessQueueThread()
The RosProcessQueueThread function is a ROS helper function that processes messages.
SerialCommunication serialInterface2
The serial interface used to communicate with the second Teensy.
void SerialProcessQueueThread()
The SerialProcessQueueThread function is a helper function that processes serial messages.
void RosPublishQueueThread()
The RosPublishQueueThread function is a ROS helper function that publish state messages.
const int NUM_MOTORS
The number of motors to interface with.
void SetJointPositions(const std::vector< double > &_pos)
Set the position of the joints.
void OnJointStateCmdMsg(const sensor_msgs::JointStateConstPtr &_msg)
The OnGenCoordMsg function handles an incoming generalized coordinates message from ROS.
virtual ~MotorInterface()
Destructor.
void SetJointTorques(const std::vector< double > &_torque)
Set the torque of the joints.
static constexpr int MAX_NUM_MOTORS_PER_PORT
The maximum numbers of motors to be interfaced with by one Teensy.
ros::CallbackQueue rosPublishQueue
ROS callbackque that helps publish messages.
ros::Publisher jointStatePub
ROS Joint State Publisher.
void InitRos()
The InitRos function is called to initialize ROS.
sensor_msgs::JointState jointStateMsg
Joint State Message.
std::thread serialProcessQueueThread
Thread running the serialProcessQueue.
ros::Subscriber jointStateCmdSub
ROS Joint State Command Subscriber.
ros::ServiceServer shutdownService
ROS Shutdown Service.
MotorInterface()
Default Constructor.
SerialCommunication serialInterface1
The serial interface used to communicate with the first Teensy.
bool Shutdown(const std_srvs::Empty::Request &_req, std_srvs::Empty::Response &_res)
The Shutdown function handles an incoming shutdown service request.
ros::CallbackQueue rosProcessQueue
ROS callbackque that helps process messages.
std::unique_ptr< ros::NodeHandle > rosNode
Node used for ROS transport.
int num_motors_port_1
The number of motors interfaced by the first Teensy.
void SetJointVelocities(const std::vector< double > &_vel)
Set the velocity of the joints.
A class for serial communication.