Tetrapod Project
MotorInterface Class Reference

A class to control and distribute motor position, velocity and torque information. More...

#include <motor_interface.h>

Collaboration diagram for MotorInterface:

Public Member Functions

 MotorInterface ()
 Default Constructor. More...
 
 MotorInterface (const int &_num_motors)
 Custom Constructor. More...
 
virtual ~MotorInterface ()
 Destructor. More...
 
void SetJointPositions (const std::vector< double > &_pos)
 Set the position of the joints. More...
 
void SetJointVelocities (const std::vector< double > &_vel)
 Set the velocity of the joints. More...
 
void SetJointTorques (const std::vector< double > &_torque)
 Set the torque of the joints. More...
 
void ProcessSerialMessages ()
 Checks if there are any incomming messages from the serial ports. If there are new replies these are read and published. More...
 
void OnJointStateCmdMsg (const sensor_msgs::JointStateConstPtr &_msg)
 The OnGenCoordMsg function handles an incoming generalized coordinates message from ROS. More...
 
void SerialProcessQueueThread ()
 The SerialProcessQueueThread function is a helper function that processes serial messages. More...
 
void RosProcessQueueThread ()
 The RosProcessQueueThread function is a ROS helper function that processes messages. More...
 
void RosPublishQueueThread ()
 The RosPublishQueueThread function is a ROS helper function that publish state messages. More...
 
bool Shutdown (const std_srvs::Empty::Request &_req, std_srvs::Empty::Response &_res)
 The Shutdown function handles an incoming shutdown service request. More...
 

Protected Member Functions

void InitRos ()
 The InitRos function is called to initialize ROS. More...
 
void InitRosQueueThreads ()
 The InitRosQueueThreads function is called to initialize the ROS Publish and Process Queue Threads. More...
 

Private Attributes

const int NUM_MOTORS
 The number of motors to interface with. More...
 
int num_motors_port_1
 The number of motors interfaced by the first Teensy. More...
 
int num_motors_port_2
 The number of motors interfaced by the second Teensy. More...
 
SerialCommunication serialInterface1
 The serial interface used to communicate with the first Teensy. More...
 
SerialCommunication serialInterface2
 The serial interface used to communicate with the second Teensy. More...
 
std::unique_ptr< ros::NodeHandle > rosNode
 Node used for ROS transport. More...
 
sensor_msgs::JointState jointStateMsg
 Joint State Message. More...
 
ros::ServiceServer shutdownService
 ROS Shutdown Service. More...
 
ros::Subscriber jointStateCmdSub
 ROS Joint State Command Subscriber. More...
 
ros::Publisher jointStatePub
 ROS Joint State Publisher. More...
 
ros::CallbackQueue rosProcessQueue
 ROS callbackque that helps process messages. More...
 
ros::CallbackQueue rosPublishQueue
 ROS callbackque that helps publish messages. More...
 
std::thread serialProcessQueueThread
 Thread running the serialProcessQueue. More...
 
std::thread rosProcessQueueThread
 Thread running the rosProcessQueue. More...
 
std::thread rosPublishQueueThread
 Thread running the rosPublishQueue. More...
 

Static Private Attributes

static constexpr int MAX_NUM_MOTORS_PER_PORT = 6
 The maximum numbers of motors to be interfaced with by one Teensy. More...
 

Detailed Description

A class to control and distribute motor position, velocity and torque information.

Definition at line 48 of file motor_interface.h.

Constructor & Destructor Documentation

◆ MotorInterface() [1/2]

MotorInterface::MotorInterface ( )

Default Constructor.

Definition at line 30 of file motor_interface.cpp.

◆ MotorInterface() [2/2]

MotorInterface::MotorInterface ( const int &  _num_motors)

Custom Constructor.

Parameters
[in]_num_motorsNumber of motors in use.

Definition at line 44 of file motor_interface.cpp.

◆ ~MotorInterface()

MotorInterface::~MotorInterface ( )
virtual

Destructor.

Definition at line 83 of file motor_interface.cpp.

Member Function Documentation

◆ SetJointPositions()

void MotorInterface::SetJointPositions ( const std::vector< double > &  _pos)

Set the position of the joints.

Parameters
[in]_posNew target position vector in radians

Definition at line 96 of file motor_interface.cpp.

◆ SetJointVelocities()

void MotorInterface::SetJointVelocities ( const std::vector< double > &  _vel)

Set the velocity of the joints.

Parameters
[in]_velNew target velocity

Definition at line 112 of file motor_interface.cpp.

◆ SetJointTorques()

void MotorInterface::SetJointTorques ( const std::vector< double > &  _torque)

Set the torque of the joints.

Parameters
[in]_torqueNew target torque

Definition at line 128 of file motor_interface.cpp.

◆ ProcessSerialMessages()

void MotorInterface::ProcessSerialMessages ( )

Checks if there are any incomming messages from the serial ports. If there are new replies these are read and published.

Definition at line 144 of file motor_interface.cpp.

◆ OnJointStateCmdMsg()

void MotorInterface::OnJointStateCmdMsg ( const sensor_msgs::JointStateConstPtr &  _msg)

The OnGenCoordMsg function handles an incoming generalized coordinates message from ROS.

Parameters
[in]_msgA float array containing the generalized coordinates.

Definition at line 192 of file motor_interface.cpp.

◆ SerialProcessQueueThread()

void MotorInterface::SerialProcessQueueThread ( )

The SerialProcessQueueThread function is a helper function that processes serial messages.

Definition at line 215 of file motor_interface.cpp.

◆ RosProcessQueueThread()

void MotorInterface::RosProcessQueueThread ( )

The RosProcessQueueThread function is a ROS helper function that processes messages.

Definition at line 228 of file motor_interface.cpp.

◆ RosPublishQueueThread()

void MotorInterface::RosPublishQueueThread ( )

The RosPublishQueueThread function is a ROS helper function that publish state messages.

Definition at line 238 of file motor_interface.cpp.

◆ Shutdown()

bool MotorInterface::Shutdown ( const std_srvs::Empty::Request &  _req,
std_srvs::Empty::Response &  _res 
)

The Shutdown function handles an incoming shutdown service request.

Parameters
[in]_reqService request.
[out]_resService response.
Returns
Returns true if success, and false if not.

Definition at line 251 of file motor_interface.cpp.

◆ InitRos()

void MotorInterface::InitRos ( )
protected

The InitRos function is called to initialize ROS.

Definition at line 260 of file motor_interface.cpp.

◆ InitRosQueueThreads()

void MotorInterface::InitRosQueueThreads ( )
protected

The InitRosQueueThreads function is called to initialize the ROS Publish and Process Queue Threads.

Definition at line 316 of file motor_interface.cpp.

Member Data Documentation

◆ MAX_NUM_MOTORS_PER_PORT

constexpr int MotorInterface::MAX_NUM_MOTORS_PER_PORT = 6
staticconstexprprivate

The maximum numbers of motors to be interfaced with by one Teensy.

Definition at line 51 of file motor_interface.h.

◆ NUM_MOTORS

const int MotorInterface::NUM_MOTORS
private

The number of motors to interface with.

Definition at line 113 of file motor_interface.h.

◆ num_motors_port_1

int MotorInterface::num_motors_port_1
private

The number of motors interfaced by the first Teensy.

Definition at line 116 of file motor_interface.h.

◆ num_motors_port_2

int MotorInterface::num_motors_port_2
private

The number of motors interfaced by the second Teensy.

Definition at line 119 of file motor_interface.h.

◆ serialInterface1

SerialCommunication MotorInterface::serialInterface1
private

The serial interface used to communicate with the first Teensy.

Definition at line 122 of file motor_interface.h.

◆ serialInterface2

SerialCommunication MotorInterface::serialInterface2
private

The serial interface used to communicate with the second Teensy.

Definition at line 125 of file motor_interface.h.

◆ rosNode

std::unique_ptr<ros::NodeHandle> MotorInterface::rosNode
private

Node used for ROS transport.

Definition at line 128 of file motor_interface.h.

◆ jointStateMsg

sensor_msgs::JointState MotorInterface::jointStateMsg
private

Joint State Message.

Definition at line 131 of file motor_interface.h.

◆ shutdownService

ros::ServiceServer MotorInterface::shutdownService
private

ROS Shutdown Service.

Definition at line 134 of file motor_interface.h.

◆ jointStateCmdSub

ros::Subscriber MotorInterface::jointStateCmdSub
private

ROS Joint State Command Subscriber.

Definition at line 137 of file motor_interface.h.

◆ jointStatePub

ros::Publisher MotorInterface::jointStatePub
private

ROS Joint State Publisher.

Definition at line 140 of file motor_interface.h.

◆ rosProcessQueue

ros::CallbackQueue MotorInterface::rosProcessQueue
private

ROS callbackque that helps process messages.

Definition at line 143 of file motor_interface.h.

◆ rosPublishQueue

ros::CallbackQueue MotorInterface::rosPublishQueue
private

ROS callbackque that helps publish messages.

Definition at line 146 of file motor_interface.h.

◆ serialProcessQueueThread

std::thread MotorInterface::serialProcessQueueThread
private

Thread running the serialProcessQueue.

Definition at line 149 of file motor_interface.h.

◆ rosProcessQueueThread

std::thread MotorInterface::rosProcessQueueThread
private

Thread running the rosProcessQueue.

Definition at line 152 of file motor_interface.h.

◆ rosPublishQueueThread

std::thread MotorInterface::rosPublishQueueThread
private

Thread running the rosPublishQueue.

Definition at line 155 of file motor_interface.h.


The documentation for this class was generated from the following files: