Tetrapod Project
single_leg_plugin.h
Go to the documentation of this file.
1 /*******************************************************************/
2 /* AUTHOR: Paal Arthur S. Thorseth & Adrian B. Ghansah */
3 /* ORGN: Dept of Eng Cybernetics, NTNU Trondheim */
4 /* FILE: single_leg_plugin.h */
5 /* DATE: Feb 4, 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/Float32.h"
44 #include "std_msgs/Float64MultiArray.h"
45 #include "sensor_msgs/JointState.h"
46 #include "std_srvs/Empty.h"
47 
48 // ROS Package Libraries
50 
51 // Eigen
52 #include <Eigen/Core>
53 
54 // Standard library
55 #include <vector>
56 #include <map>
57 
58 namespace gazebo
59 {
61  static constexpr unsigned int NUMJOINTS = 3;
62 
63  using JointVelocities = Eigen::Matrix<double, 3, 1>;
64 
65  enum ControlMode { position = 1, velocity = 2, torque = 3 };
66 
68  class SingleLegPlugin : public ModelPlugin
69  {
70 
72  public: SingleLegPlugin();
73 
75  public: virtual ~SingleLegPlugin();
76 
82  public: virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
83 
87  public: Eigen::Matrix<double, 6, 1> GetBasePose();
88 
93  public: Eigen::Matrix<double, 6, 1> GetBaseTwist();
94 
98  public: double GetJointForce(const std::string &_joint_name);
99 
102  public: Eigen::Matrix<double, 3, 1> GetJointForces();
103 
107  public: double GetJointVelocity(const std::string &_joint_name);
108 
111  public: Eigen::Matrix<double, 3, 1> GetJointVelocities();
112 
116  public: double GetJointPosition(const std::string &_joint_name);
117 
120  public: Eigen::Matrix<double, 3, 1> GetJointPositions();
121 
125  public: void SetJointForce(const std::string &_joint_name, const double &_force);
126 
129  public: void SetJointForces(const std::vector<double> &_forces);
130 
134  public: void SetJointVelocity(const std::string &_joint_name, const double &_vel);
135 
138  public: void SetJointVelocities(const std::vector<double> &_vel);
139 
142  public: void SetJointPositions(const std::vector<double> &_pos);
143 
151  public: void OnJointStateMsg(const sensor_msgs::JointStateConstPtr &_msg);
152 
157  public: void OnForceMsg(const std_msgs::Float64MultiArrayConstPtr &_msg);
158 
163  public: void OnVelMsg(const std_msgs::Float64MultiArrayConstPtr &_msg);
164 
169  public: void OnPosMsg(const std_msgs::Float64MultiArrayConstPtr &_msg);
170 
173  public: void ProcessQueueThread();
174 
177  public: void PublishQueueThread();
178 
179  // TODO REMOVE
180  public: void printMap(const std::map<std::string,physics::JointPtr> &_map);
181 
183  protected: void InitRos();
184 
187  protected: void InitRosQueueThreads();
188 
192  protected: bool LoadParametersRos();
193 
196  protected: void InitJointControllers();
197 
200  protected: void InitJointConfiguration();
201 
207  public: bool ResetSimulation(const std_srvs::Empty::Request &_req,
208  std_srvs::Empty::Response &_res);
209 
211  private: physics::ModelPtr model;
212 
214  private: physics::WorldPtr world;
215 
217  private: std::string model_name;
218 
220  private: physics::LinkPtr base;
221 
223  //private: std::vector<physics::JointPtr> joints;
224  //private: physics::Joint_V joints;
225  private: std::map<std::string, physics::JointPtr> joints;
226 
228  private: std::vector<std::string> joint_names;
229 
231  private: std::vector<double> joint_config;
232 
234  private: std::vector<double> vel_p_gains;
235 
237  private: std::vector<double> vel_i_gains;
238 
240  private: std::vector<double> vel_d_gains;
241 
243  private: std::vector<double> pos_p_gains;
244 
246  private: std::vector<double> pos_i_gains;
247 
249  private: std::vector<double> pos_d_gains;
250 
254 
256  private: std::unique_ptr<ros::NodeHandle> rosNode;
257 
259  private: ros::ServiceServer resetSimService;
260 
262  private: ros::Publisher genCoordPub;
263 
265  private: ros::Publisher genVelPub;
266 
268  private: ros::Publisher jointForcesPub;
269 
271  private: ros::Subscriber jointStateSub;
272 
274  private: ros::Subscriber forceSub;
275 
277  private: ros::Subscriber velSub;
278 
280  private: ros::Subscriber posSub;
281 
283  private: ros::CallbackQueue rosProcessQueue;
284 
286  private: ros::CallbackQueue rosPublishQueue;
287 
289  private: std::thread rosProcessQueueThread;
290 
292  private: std::thread rosPublishQueueThread;
293  };
294 
295  // Tell Gazebo about this plugin, so that Gazebo can call Load on this plugin.
296  GZ_REGISTER_MODEL_PLUGIN(SingleLegPlugin)
297 } // namespace gazebo
A plugin to control the single_leg robot.
void OnForceMsg(const std_msgs::Float64MultiArrayConstPtr &_msg)
The OnRosMsg function handles an incoming force message from ROS.
void ProcessQueueThread()
The ProcessQueueThread function is a ROS helper function that processes messages.
std::thread rosProcessQueueThread
Thread running the rosProcessQueue.
ros::Subscriber posSub
ROS Position Subscriber.
void SetJointPositions(const std::vector< double > &_pos)
Set the position of the joints.
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
The Load function is called by Gazebo when the plugin is inserted into simulation.
virtual ~SingleLegPlugin()
Destructor.
double GetJointPosition(const std::string &_joint_name)
Get current position at a specific joint.
ros::Subscriber forceSub
ROS Force Subscriber.
Eigen::Matrix< double, 6, 1 > GetBaseTwist()
Get current base twist for the robot.
Eigen::Matrix< double, 6, 1 > GetBasePose()
Get current base pose for the robot.
bool LoadParametersRos()
The LoadParametersRos function is called to load conffloatiguration from the parameter server.
std::vector< double > vel_i_gains
Vector of Velocity I-gains.
double GetJointVelocity(const std::string &_joint_name)
Get current velocity at a specific joint.
std::vector< double > joint_config
Vector of joint configuration.
ros::Publisher genCoordPub
ROS Generalized Coordinates Publisher.
void SetJointForce(const std::string &_joint_name, const double &_force)
Apply force at a specific joint.
void OnJointStateMsg(const sensor_msgs::JointStateConstPtr &_msg)
The OnJointStateMsg function handles an incoming joint state message from ROS.
Eigen::Matrix< double, 3, 1 > GetJointPositions()
Get current joint positions for the robot.
std::string model_name
Model name.
ros::Publisher jointForcesPub
ROS Joint Forces (Torques) Publisher.
void InitRos()
The initRos function is called to initialize ROS.
physics::LinkPtr base
Pointer to the body link.
std::unique_ptr< ros::NodeHandle > rosNode
Node used for ROS transport.
std::vector< double > vel_p_gains
Vector of Velocity P-gains.
std::map< std::string, physics::JointPtr > joints
Pointers to the joints.
void PublishQueueThread()
The PublishQueueThread function is a ROS helper function that publish state messages.
std::vector< double > pos_i_gains
Vector of Position I-gains.
Eigen::Matrix< double, 3, 1 > GetJointVelocities()
Get current joint velocities for the robot.
physics::WorldPtr world
Pointer to the world.
ControlMode controlMode
Control mode indicator { position = 1, velocity = 2, torque = 3 }.
void InitJointConfiguration()
The InitJointConfiguration function is called to initialize the desired joint configuration.
void SetJointForces(const std::vector< double > &_forces)
Apply joint forces.
bool ResetSimulation(const std_srvs::Empty::Request &_req, std_srvs::Empty::Response &_res)
The ResetSimulation function handles an incoming reset simulation service request.
ros::ServiceServer resetSimService
ROS Reset Simulation Service.
void OnPosMsg(const std_msgs::Float64MultiArrayConstPtr &_msg)
The OnRosMsg function handles an incoming velocity message from ROS.
void InitRosQueueThreads()
The InitRosQueueThreads function is called to initialize the ROS Publish and Process Queue Threads.
ros::Subscriber jointStateSub
ROS Joint State Subscriber.
Eigen::Matrix< double, 3, 1 > GetJointForces()
Get current joint forces for the robot.
ros::Publisher genVelPub
ROS Generalized Velocities Publisher.
std::vector< std::string > joint_names
Vector of joint names.
double GetJointForce(const std::string &_joint_name)
Get currently applied force at a specific joint.
void InitJointControllers()
The InitJointControllers function is called to setup joint PID controllers.
ros::CallbackQueue rosPublishQueue
ROS callbackque that helps publish messages.
std::vector< double > vel_d_gains
Vector of Velocity D-gains.
ros::CallbackQueue rosProcessQueue
ROS callbackque that helps process messages.
ros::Subscriber velSub
ROS Velocity Subscriber.
void SetJointVelocity(const std::string &_joint_name, const double &_vel)
Set the velocity of the joint.
std::thread rosPublishQueueThread
Thread running the rosPublishQueue.
std::vector< double > pos_d_gains
Vector of Position D-gains.
physics::ModelPtr model
Pointer to the model.
void printMap(const std::map< std::string, physics::JointPtr > &_map)
std::vector< double > pos_p_gains
Vector of Position P-gains.
void SetJointVelocities(const std::vector< double > &_vel)
Set the velocity of the joints.
void OnVelMsg(const std_msgs::Float64MultiArrayConstPtr &_msg)
The OnRosMsg function handles an incoming velocity message from ROS.
Eigen::Matrix< double, 3, 1 > JointVelocities
static constexpr unsigned int NUMJOINTS
Fixed variable for num joints.