Tetrapod Project
gazebo::PendulumPlugin Class Reference

A plugin to control the pendulum robot. More...

#include <pendulum_plugin.h>

Inheritance diagram for gazebo::PendulumPlugin:
Collaboration diagram for gazebo::PendulumPlugin:

Public Types

enum  ControlMode { position = 1 , velocity = 2 , torque = 3 }
 Control mode enumerator. More...
 

Public Member Functions

 PendulumPlugin ()
 Constructor. More...
 
virtual ~PendulumPlugin ()
 Destructor. More...
 
virtual void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 The Load function is called by Gazebo when the plugin is inserted into simulation. More...
 
double GetJointForce ()
 Get currently applied force at the joint. More...
 
void SetJointForce (const double &_force)
 Apply force at a specific joint. More...
 
void SetJointVelocity (const double &_vel)
 Set the velocity of the joint. More...
 
void SetJointPosition (const double &_pos)
 Set the position of the joint. More...
 
void OnJointStateMsg (const sensor_msgs::JointStateConstPtr &_msg)
 The OnJointStateMsg function handles an incoming joint state message from ROS. More...
 
void ProcessQueueThread ()
 The ProcessQueueThread function is a ROS helper function that processes messages. More...
 
void PublishQueueThread ()
 The PublishQueueThread function is a ROS helper function that publish state messages. 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...
 
void InitJointController ()
 The InitJointControllers function is called to setup joint PID controllers. More...
 
void InitJointConfiguration ()
 The InitJointConfiguration function is called to initialize the desired joint configuration. More...
 

Private Attributes

physics::ModelPtr model
 Pointer to the model. More...
 
std::string model_name
 Model name. More...
 
physics::JointPtr joint
 Pointers to the joint. More...
 
double vel_p_gain
 Velocity P-gain. More...
 
double vel_i_gain
 Velocity I-gain. More...
 
double vel_d_gain
 Velocity D-gain. More...
 
double pos_p_gain
 Position P-gain. More...
 
double pos_i_gain
 Position I-gain. More...
 
double pos_d_gain
 Position D-gain. More...
 
ControlMode controlMode
 Control mode indicator { position = 1, velocity = 2, torque = 3 }. More...
 
std::unique_ptr< ros::NodeHandle > rosNode
 Node used for ROS transport. More...
 
ros::Subscriber jointStateSub
 ROS Joint State Subscriber. More...
 
ros::Publisher jointForcePub
 ROS Joint Force (Torque) Publisher. More...
 
ros::CallbackQueue rosProcessQueue
 ROS callbackque that helps process messages. More...
 
ros::CallbackQueue rosPublishQueue
 ROS callbackque that helps publish messages. More...
 
std::thread rosProcessQueueThread
 Thread running the rosProcessQueue. More...
 
std::thread rosPublishQueueThread
 Thread running the rosPublishQueue. More...
 

Detailed Description

A plugin to control the pendulum robot.

Definition at line 63 of file pendulum_plugin.h.

Member Enumeration Documentation

◆ ControlMode

Control mode enumerator.

Enumerator
position 
velocity 
torque 

Definition at line 66 of file pendulum_plugin.h.

Constructor & Destructor Documentation

◆ PendulumPlugin()

gazebo::PendulumPlugin::PendulumPlugin ( )

Constructor.

Definition at line 34 of file pendulum_plugin.cpp.

◆ ~PendulumPlugin()

gazebo::PendulumPlugin::~PendulumPlugin ( )
virtual

Destructor.

Definition at line 46 of file pendulum_plugin.cpp.

Member Function Documentation

◆ Load()

void gazebo::PendulumPlugin::Load ( physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
)
virtual

The Load function is called by Gazebo when the plugin is inserted into simulation.

Parameters
[in]_modelA pointer to the model that the plugin is attached to.
[in]_sdfA pointer to the plugin's SDF element.

Definition at line 56 of file pendulum_plugin.cpp.

◆ GetJointForce()

double gazebo::PendulumPlugin::GetJointForce ( )

Get currently applied force at the joint.

Returns
Current joint force

Definition at line 81 of file pendulum_plugin.cpp.

◆ SetJointForce()

void gazebo::PendulumPlugin::SetJointForce ( const double &  _force)

Apply force at a specific joint.

Parameters
[in]_forceForce to apply

Definition at line 89 of file pendulum_plugin.cpp.

◆ SetJointVelocity()

void gazebo::PendulumPlugin::SetJointVelocity ( const double &  _vel)

Set the velocity of the joint.

Parameters
[in]_velNew target velocity

Definition at line 106 of file pendulum_plugin.cpp.

◆ SetJointPosition()

void gazebo::PendulumPlugin::SetJointPosition ( const double &  _pos)

Set the position of the joint.

Parameters
[in]_posNew target position in radians

Definition at line 123 of file pendulum_plugin.cpp.

◆ OnJointStateMsg()

void gazebo::PendulumPlugin::OnJointStateMsg ( const sensor_msgs::JointStateConstPtr &  _msg)

The OnJointStateMsg function handles an incoming joint state message from ROS.

Parameters
[in]_msgA message holding data to describe the state of a set of controlled joints. The state is defined by
  • the position of the joint,
  • the velocity of the joint and
  • the effort (torque) that is applied in the joint.

Definition at line 139 of file pendulum_plugin.cpp.

◆ ProcessQueueThread()

void gazebo::PendulumPlugin::ProcessQueueThread ( )

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

Definition at line 158 of file pendulum_plugin.cpp.

◆ PublishQueueThread()

void gazebo::PendulumPlugin::PublishQueueThread ( )

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

Definition at line 168 of file pendulum_plugin.cpp.

◆ InitRos()

void gazebo::PendulumPlugin::InitRos ( )
protected

The initRos function is called to initialize ROS.

Definition at line 183 of file pendulum_plugin.cpp.

◆ InitRosQueueThreads()

void gazebo::PendulumPlugin::InitRosQueueThreads ( )
protected

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

Definition at line 224 of file pendulum_plugin.cpp.

◆ InitJointController()

void gazebo::PendulumPlugin::InitJointController ( )
protected

The InitJointControllers function is called to setup joint PID controllers.

Definition at line 236 of file pendulum_plugin.cpp.

◆ InitJointConfiguration()

void gazebo::PendulumPlugin::InitJointConfiguration ( )
protected

The InitJointConfiguration function is called to initialize the desired joint configuration.

Definition at line 250 of file pendulum_plugin.cpp.

Member Data Documentation

◆ model

physics::ModelPtr gazebo::PendulumPlugin::model
private

Pointer to the model.

Definition at line 130 of file pendulum_plugin.h.

◆ model_name

std::string gazebo::PendulumPlugin::model_name
private

Model name.

Definition at line 133 of file pendulum_plugin.h.

◆ joint

physics::JointPtr gazebo::PendulumPlugin::joint
private

Pointers to the joint.

Definition at line 136 of file pendulum_plugin.h.

◆ vel_p_gain

double gazebo::PendulumPlugin::vel_p_gain
private

Velocity P-gain.

Definition at line 139 of file pendulum_plugin.h.

◆ vel_i_gain

double gazebo::PendulumPlugin::vel_i_gain
private

Velocity I-gain.

Definition at line 142 of file pendulum_plugin.h.

◆ vel_d_gain

double gazebo::PendulumPlugin::vel_d_gain
private

Velocity D-gain.

Definition at line 145 of file pendulum_plugin.h.

◆ pos_p_gain

double gazebo::PendulumPlugin::pos_p_gain
private

Position P-gain.

Definition at line 148 of file pendulum_plugin.h.

◆ pos_i_gain

double gazebo::PendulumPlugin::pos_i_gain
private

Position I-gain.

Definition at line 151 of file pendulum_plugin.h.

◆ pos_d_gain

double gazebo::PendulumPlugin::pos_d_gain
private

Position D-gain.

Definition at line 154 of file pendulum_plugin.h.

◆ controlMode

ControlMode gazebo::PendulumPlugin::controlMode
private

Control mode indicator { position = 1, velocity = 2, torque = 3 }.

Definition at line 158 of file pendulum_plugin.h.

◆ rosNode

std::unique_ptr<ros::NodeHandle> gazebo::PendulumPlugin::rosNode
private

Node used for ROS transport.

Definition at line 161 of file pendulum_plugin.h.

◆ jointStateSub

ros::Subscriber gazebo::PendulumPlugin::jointStateSub
private

ROS Joint State Subscriber.

Definition at line 164 of file pendulum_plugin.h.

◆ jointForcePub

ros::Publisher gazebo::PendulumPlugin::jointForcePub
private

ROS Joint Force (Torque) Publisher.

Definition at line 167 of file pendulum_plugin.h.

◆ rosProcessQueue

ros::CallbackQueue gazebo::PendulumPlugin::rosProcessQueue
private

ROS callbackque that helps process messages.

Definition at line 170 of file pendulum_plugin.h.

◆ rosPublishQueue

ros::CallbackQueue gazebo::PendulumPlugin::rosPublishQueue
private

ROS callbackque that helps publish messages.

Definition at line 173 of file pendulum_plugin.h.

◆ rosProcessQueueThread

std::thread gazebo::PendulumPlugin::rosProcessQueueThread
private

Thread running the rosProcessQueue.

Definition at line 176 of file pendulum_plugin.h.

◆ rosPublishQueueThread

std::thread gazebo::PendulumPlugin::rosPublishQueueThread
private

Thread running the rosPublishQueue.

Definition at line 179 of file pendulum_plugin.h.


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