Tetrapod Project
pendulum_plugin.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: pendulum_plugin.h */
5 /* DATE: May 5, 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 // Gazebo
30 #include <gazebo/gazebo.hh>
31 #include <gazebo/physics/physics.hh>
32 #include <gazebo/transport/transport.hh>
33 #include <gazebo/msgs/msgs.hh>
34 
35 // ROS
36 #include <thread>
37 #include "ros/ros.h"
38 #include "ros/package.h"
39 #include "ros/console.h"
40 #include "ros/callback_queue.h"
41 #include "ros/subscribe_options.h"
42 #include "eigen_conversions/eigen_msg.h"
43 #include "std_msgs/Float64.h"
44 #include "std_msgs/Float64MultiArray.h"
45 #include "sensor_msgs/JointState.h"
46 
47 // ROS Package Libraries
49 
50 // Eigen
51 #include <Eigen/Core>
52 
53 // Standard library
54 #include <vector>
55 #include <map>
56 
57 namespace gazebo
58 {
60  static constexpr unsigned int NUMJOINTS = 1;
61 
63  class PendulumPlugin : public ModelPlugin
64  {
66  public: enum ControlMode { position = 1, velocity = 2, torque = 3 };
67 
69  public: PendulumPlugin();
70 
72  public: virtual ~PendulumPlugin();
73 
79  public: virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
80 
83  public: double GetJointForce();
84 
87  public: void SetJointForce(const double &_force);
88 
91  public: void SetJointVelocity(const double &_vel);
92 
95  public: void SetJointPosition(const double &_pos);
96 
104  public: void OnJointStateMsg(const sensor_msgs::JointStateConstPtr &_msg);
105 
108  public: void ProcessQueueThread();
109 
112  public: void PublishQueueThread();
113 
115  protected: void InitRos();
116 
119  protected: void InitRosQueueThreads();
120 
123  protected: void InitJointController();
124 
127  protected: void InitJointConfiguration();
128 
130  private: physics::ModelPtr model;
131 
133  private: std::string model_name;
134 
136  private: physics::JointPtr joint;
137 
139  private: double vel_p_gain;
140 
142  private: double vel_i_gain;
143 
145  private: double vel_d_gain;
146 
148  private: double pos_p_gain;
149 
151  private: double pos_i_gain;
152 
154  private: double pos_d_gain;
155 
159 
161  private: std::unique_ptr<ros::NodeHandle> rosNode;
162 
164  private: ros::Subscriber jointStateSub;
165 
167  private: ros::Publisher jointForcePub;
168 
170  private: ros::CallbackQueue rosProcessQueue;
171 
173  private: ros::CallbackQueue rosPublishQueue;
174 
176  private: std::thread rosProcessQueueThread;
177 
179  private: std::thread rosPublishQueueThread;
180 
181  };
182 
183  // Tell Gazebo about this plugin, so that Gazebo can call Load on this plugin.
184  GZ_REGISTER_MODEL_PLUGIN(PendulumPlugin)
185 } // namespace gazebo
A plugin to control the pendulum robot.
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
The Load function is called by Gazebo when the plugin is inserted into simulation.
void SetJointPosition(const double &_pos)
Set the position of the joint.
std::thread rosPublishQueueThread
Thread running the rosPublishQueue.
void OnJointStateMsg(const sensor_msgs::JointStateConstPtr &_msg)
The OnJointStateMsg function handles an incoming joint state message from ROS.
std::string model_name
Model name.
ControlMode
Control mode enumerator.
ros::Publisher jointForcePub
ROS Joint Force (Torque) Publisher.
double pos_d_gain
Position D-gain.
void SetJointVelocity(const double &_vel)
Set the velocity of the joint.
PendulumPlugin()
Constructor.
double vel_i_gain
Velocity I-gain.
ros::CallbackQueue rosPublishQueue
ROS callbackque that helps publish messages.
double vel_d_gain
Velocity D-gain.
double pos_i_gain
Position I-gain.
void InitJointController()
The InitJointControllers function is called to setup joint PID controllers.
physics::ModelPtr model
Pointer to the model.
void SetJointForce(const double &_force)
Apply force at a specific joint.
physics::JointPtr joint
Pointers to the joint.
double pos_p_gain
Position P-gain.
ros::Subscriber jointStateSub
ROS Joint State Subscriber.
double GetJointForce()
Get currently applied force at the joint.
std::unique_ptr< ros::NodeHandle > rosNode
Node used for ROS transport.
std::thread rosProcessQueueThread
Thread running the rosProcessQueue.
void InitRos()
The initRos function is called to initialize ROS.
ControlMode controlMode
Control mode indicator { position = 1, velocity = 2, torque = 3 }.
ros::CallbackQueue rosProcessQueue
ROS callbackque that helps process messages.
void InitRosQueueThreads()
The InitRosQueueThreads function is called to initialize the ROS Publish and Process Queue Threads.
void ProcessQueueThread()
The ProcessQueueThread function is a ROS helper function that processes messages.
void InitJointConfiguration()
The InitJointConfiguration function is called to initialize the desired joint configuration.
double vel_p_gain
Velocity P-gain.
void PublishQueueThread()
The PublishQueueThread function is a ROS helper function that publish state messages.
virtual ~PendulumPlugin()
Destructor.
static constexpr unsigned int NUMJOINTS
Fixed variable for num joints.