Tetrapod Project
log_utils.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: log_utils.h */
5 /* DATE: Jun 12, 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 // C++ Standard Library
30 #include <thread>
31 
32 // ROS
33 #include "ros/ros.h"
34 #include "ros/callback_queue.h"
35 
36 // ROS messages
37 #include "std_msgs/Int8MultiArray.h"
38 #include "std_msgs/Float64MultiArray.h"
39 #include "sensor_msgs/JointState.h"
40 
41 // ROS Package Libraries
42 #include <kinematics/kinematics.h>
43 
44 // Eigen
45 #include <Eigen/Core>
46 
48 class LogUtils
49 {
51  public: LogUtils();
52 
54  public: virtual ~LogUtils();
55 
56  // TODO Describe
57  public: void WriteToLog();
58 
63  public: void OnGenCoordMsg(const std_msgs::Float64MultiArrayConstPtr &_msg);
64 
69  public: void OnGenVelMsg(const std_msgs::Float64MultiArrayConstPtr &_msg);
70 
78  public: void OnJointStateMsg(const sensor_msgs::JointStateConstPtr &_msg);
79 
87  public: void OnJointStateCmdMsg(const sensor_msgs::JointStateConstPtr &_msg);
88 
91  public: void PublishQueueThread();
92 
95  public: void ProcessQueueThread();
96 
98  protected: void InitRos();
99 
102  protected: void InitRosQueueThreads();
103 
106 
108  private: Eigen::Matrix<double, 18, 1> genCoord;
109 
111  private: Eigen::Matrix<double, 18, 1> genVel;
112 
114  private: sensor_msgs::JointState jointState;
115 
117  private: sensor_msgs::JointState jointStateCmd;
118 
120  private: Eigen::Matrix<Eigen::Vector3d, 4, 1> fPos;
121 
123  private: int contactState[4];
124 
126  private: std::unique_ptr<ros::NodeHandle> rosNode;
127 
129  private: ros::Subscriber genCoordSub;
130 
132  private: ros::Subscriber genVelSub;
133 
135  private: ros::Subscriber jointStateSub;
136 
138  private: ros::Subscriber jointStateCmdSub;
139 
141  private: ros::Subscriber contactStateSub;
142 
144  private: ros::Publisher genCoordLogPub;
145 
147  private: ros::Publisher genVelLogPub;
148 
150  private: ros::Publisher jointStatePub;
151 
153  private: ros::Publisher jointStateCmdPub;
154 
156  private: ros::CallbackQueue rosPublishQueue;
157 
159  private: ros::CallbackQueue rosProcessQueue;
160 
162  private: std::thread rosPublishQueueThread;
163 
165  private: std::thread rosProcessQueueThread;
166 };
A class for analytical Kinematics Solving.
Definition: kinematics.h:54
A class for logging utilities.
Definition: log_utils.h:49
void InitRos()
The InitRos function is called to initialize ROS.
Definition: log_utils.cpp:134
LogUtils()
Constructor.
Definition: log_utils.cpp:30
std::unique_ptr< ros::NodeHandle > rosNode
Node used for ROS transport.
Definition: log_utils.h:126
ros::Subscriber genVelSub
ROS Generalized Coordinates Subscriber.
Definition: log_utils.h:132
void ProcessQueueThread()
The ProcessQueueThread function is a ROS helper function that processes messages.
Definition: log_utils.cpp:124
sensor_msgs::JointState jointStateCmd
Joint State Command.
Definition: log_utils.h:117
void OnGenCoordMsg(const std_msgs::Float64MultiArrayConstPtr &_msg)
The OnGenCoordMsg function handles an incoming generalized coordinates message from ROS.
Definition: log_utils.cpp:69
std::thread rosProcessQueueThread
Thread running the rosProcessQueue.
Definition: log_utils.h:165
virtual ~LogUtils()
Destructor.
Definition: log_utils.cpp:43
Eigen::Matrix< Eigen::Vector3d, 4, 1 > fPos
Footstep positions.
Definition: log_utils.h:120
sensor_msgs::JointState jointState
Joint State.
Definition: log_utils.h:114
void OnGenVelMsg(const std_msgs::Float64MultiArrayConstPtr &_msg)
The OnGenVelMsg function handles an incoming generalized velocities message from ROS.
Definition: log_utils.cpp:87
ros::Subscriber contactStateSub
ROS Contact State Subscriber.
Definition: log_utils.h:141
std::thread rosPublishQueueThread
Thread running the rosPublishQueue.
Definition: log_utils.h:162
Kinematics kinematics
Kinematics.
Definition: log_utils.h:105
Eigen::Matrix< double, 18, 1 > genVel
Generalized Velocities.
Definition: log_utils.h:111
ros::Publisher genCoordLogPub
ROS Generalized Coordinates Log Publisher.
Definition: log_utils.h:144
Eigen::Matrix< double, 18, 1 > genCoord
Generalized Coordinates.
Definition: log_utils.h:108
ros::Subscriber jointStateSub
ROS Joint State Subscriber.
Definition: log_utils.h:135
ros::Publisher genVelLogPub
ROS Generalized Velocities Log Publisher.
Definition: log_utils.h:147
void OnJointStateMsg(const sensor_msgs::JointStateConstPtr &_msg)
The OnJointStateMsg function handles an incoming joint state message from ROS.
Definition: log_utils.cpp:96
void InitRosQueueThreads()
The InitRosQueueThreads function is called to initialize the ROS Publish and Process Queue Threads.
Definition: log_utils.cpp:245
ros::Publisher jointStateCmdPub
ROS Joint State Command Log Publisher.
Definition: log_utils.h:153
void WriteToLog()
Definition: log_utils.cpp:57
ros::Subscriber genCoordSub
ROS Generalized Coordinates Subscriber.
Definition: log_utils.h:129
void OnJointStateCmdMsg(const sensor_msgs::JointStateConstPtr &_msg)
The OnJointStateCmdMsg function handles an incoming joint state command message from ROS.
Definition: log_utils.cpp:105
ros::CallbackQueue rosProcessQueue
ROS callbackque that helps process messages.
Definition: log_utils.h:159
int contactState[4]
Contact State.
Definition: log_utils.h:123
void PublishQueueThread()
The PublishQueueThread function is a ROS helper function that publish state messages.
Definition: log_utils.cpp:114
ros::Subscriber jointStateCmdSub
ROS Joint State Command Subscriber.
Definition: log_utils.h:138
ros::Publisher jointStatePub
ROS Joint State Log Publisher.
Definition: log_utils.h:150
ros::CallbackQueue rosPublishQueue
ROS callbackque that helps publish messages.
Definition: log_utils.h:156