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"
102 public:
bool Shutdown(
const std_srvs::Empty::Request &_req,
103 std_srvs::Empty::Response &_res);
128 private: std::unique_ptr<ros::NodeHandle>
rosNode;
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.