![]() |
Tetrapod Project
|
A class to control and distribute motor position, velocity and torque information. More...
#include <motor_interface.h>

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... | |
A class to control and distribute motor position, velocity and torque information.
Definition at line 48 of file motor_interface.h.
| MotorInterface::MotorInterface | ( | ) |
Default Constructor.
Definition at line 30 of file motor_interface.cpp.
| MotorInterface::MotorInterface | ( | const int & | _num_motors | ) |
Custom Constructor.
| [in] | _num_motors | Number of motors in use. |
Definition at line 44 of file motor_interface.cpp.
|
virtual |
Destructor.
Definition at line 83 of file motor_interface.cpp.
| void MotorInterface::SetJointPositions | ( | const std::vector< double > & | _pos | ) |
Set the position of the joints.
| [in] | _pos | New target position vector in radians |
Definition at line 96 of file motor_interface.cpp.
| void MotorInterface::SetJointVelocities | ( | const std::vector< double > & | _vel | ) |
Set the velocity of the joints.
| [in] | _vel | New target velocity |
Definition at line 112 of file motor_interface.cpp.
| void MotorInterface::SetJointTorques | ( | const std::vector< double > & | _torque | ) |
Set the torque of the joints.
| [in] | _torque | New target torque |
Definition at line 128 of file motor_interface.cpp.
| 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.
| void MotorInterface::OnJointStateCmdMsg | ( | const sensor_msgs::JointStateConstPtr & | _msg | ) |
The OnGenCoordMsg function handles an incoming generalized coordinates message from ROS.
| [in] | _msg | A float array containing the generalized coordinates. |
Definition at line 192 of file motor_interface.cpp.
| void MotorInterface::SerialProcessQueueThread | ( | ) |
The SerialProcessQueueThread function is a helper function that processes serial messages.
Definition at line 215 of file motor_interface.cpp.
| void MotorInterface::RosProcessQueueThread | ( | ) |
The RosProcessQueueThread function is a ROS helper function that processes messages.
Definition at line 228 of file motor_interface.cpp.
| void MotorInterface::RosPublishQueueThread | ( | ) |
The RosPublishQueueThread function is a ROS helper function that publish state messages.
Definition at line 238 of file motor_interface.cpp.
| bool MotorInterface::Shutdown | ( | const std_srvs::Empty::Request & | _req, |
| std_srvs::Empty::Response & | _res | ||
| ) |
The Shutdown function handles an incoming shutdown service request.
| [in] | _req | Service request. |
| [out] | _res | Service response. |
Definition at line 251 of file motor_interface.cpp.
|
protected |
The InitRos function is called to initialize ROS.
Definition at line 260 of file motor_interface.cpp.
|
protected |
The InitRosQueueThreads function is called to initialize the ROS Publish and Process Queue Threads.
Definition at line 316 of file motor_interface.cpp.
|
staticconstexprprivate |
The maximum numbers of motors to be interfaced with by one Teensy.
Definition at line 51 of file motor_interface.h.
|
private |
The number of motors to interface with.
Definition at line 113 of file motor_interface.h.
|
private |
The number of motors interfaced by the first Teensy.
Definition at line 116 of file motor_interface.h.
|
private |
The number of motors interfaced by the second Teensy.
Definition at line 119 of file motor_interface.h.
|
private |
The serial interface used to communicate with the first Teensy.
Definition at line 122 of file motor_interface.h.
|
private |
The serial interface used to communicate with the second Teensy.
Definition at line 125 of file motor_interface.h.
|
private |
Node used for ROS transport.
Definition at line 128 of file motor_interface.h.
|
private |
Joint State Message.
Definition at line 131 of file motor_interface.h.
|
private |
ROS Shutdown Service.
Definition at line 134 of file motor_interface.h.
|
private |
ROS Joint State Command Subscriber.
Definition at line 137 of file motor_interface.h.
|
private |
ROS Joint State Publisher.
Definition at line 140 of file motor_interface.h.
|
private |
ROS callbackque that helps process messages.
Definition at line 143 of file motor_interface.h.
|
private |
ROS callbackque that helps publish messages.
Definition at line 146 of file motor_interface.h.
|
private |
Thread running the serialProcessQueue.
Definition at line 149 of file motor_interface.h.
|
private |
Thread running the rosProcessQueue.
Definition at line 152 of file motor_interface.h.
|
private |
Thread running the rosPublishQueue.
Definition at line 155 of file motor_interface.h.