34 #include "ros/callback_queue.h"
37 #include "std_msgs/Int8MultiArray.h"
38 #include "std_msgs/Float64MultiArray.h"
39 #include "sensor_msgs/JointState.h"
63 public:
void OnGenCoordMsg(
const std_msgs::Float64MultiArrayConstPtr &_msg);
69 public:
void OnGenVelMsg(
const std_msgs::Float64MultiArrayConstPtr &_msg);
78 public:
void OnJointStateMsg(
const sensor_msgs::JointStateConstPtr &_msg);
111 private: Eigen::Matrix<double, 18, 1>
genVel;
120 private: Eigen::Matrix<Eigen::Vector3d, 4, 1>
fPos;
126 private: std::unique_ptr<ros::NodeHandle>
rosNode;
A class for analytical Kinematics Solving.
A class for logging utilities.
void InitRos()
The InitRos function is called to initialize ROS.
std::unique_ptr< ros::NodeHandle > rosNode
Node used for ROS transport.
ros::Subscriber genVelSub
ROS Generalized Coordinates Subscriber.
void ProcessQueueThread()
The ProcessQueueThread function is a ROS helper function that processes messages.
sensor_msgs::JointState jointStateCmd
Joint State Command.
void OnGenCoordMsg(const std_msgs::Float64MultiArrayConstPtr &_msg)
The OnGenCoordMsg function handles an incoming generalized coordinates message from ROS.
std::thread rosProcessQueueThread
Thread running the rosProcessQueue.
virtual ~LogUtils()
Destructor.
Eigen::Matrix< Eigen::Vector3d, 4, 1 > fPos
Footstep positions.
sensor_msgs::JointState jointState
Joint State.
void OnGenVelMsg(const std_msgs::Float64MultiArrayConstPtr &_msg)
The OnGenVelMsg function handles an incoming generalized velocities message from ROS.
ros::Subscriber contactStateSub
ROS Contact State Subscriber.
std::thread rosPublishQueueThread
Thread running the rosPublishQueue.
Kinematics kinematics
Kinematics.
Eigen::Matrix< double, 18, 1 > genVel
Generalized Velocities.
ros::Publisher genCoordLogPub
ROS Generalized Coordinates Log Publisher.
Eigen::Matrix< double, 18, 1 > genCoord
Generalized Coordinates.
ros::Subscriber jointStateSub
ROS Joint State Subscriber.
ros::Publisher genVelLogPub
ROS Generalized Velocities Log Publisher.
void OnJointStateMsg(const sensor_msgs::JointStateConstPtr &_msg)
The OnJointStateMsg function handles an incoming joint state message from ROS.
void InitRosQueueThreads()
The InitRosQueueThreads function is called to initialize the ROS Publish and Process Queue Threads.
ros::Publisher jointStateCmdPub
ROS Joint State Command Log Publisher.
ros::Subscriber genCoordSub
ROS Generalized Coordinates Subscriber.
void OnJointStateCmdMsg(const sensor_msgs::JointStateConstPtr &_msg)
The OnJointStateCmdMsg function handles an incoming joint state command message from ROS.
ros::CallbackQueue rosProcessQueue
ROS callbackque that helps process messages.
int contactState[4]
Contact State.
void PublishQueueThread()
The PublishQueueThread function is a ROS helper function that publish state messages.
ros::Subscriber jointStateCmdSub
ROS Joint State Command Subscriber.
ros::Publisher jointStatePub
ROS Joint State Log Publisher.
ros::CallbackQueue rosPublishQueue
ROS callbackque that helps publish messages.