Tetrapod Project
|
A plugin to control the pendulum robot. More...
#include <pendulum_plugin.h>
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... | |
A plugin to control the pendulum robot.
Definition at line 63 of file pendulum_plugin.h.
Control mode enumerator.
Enumerator | |
---|---|
position | |
velocity | |
torque |
Definition at line 66 of file pendulum_plugin.h.
gazebo::PendulumPlugin::PendulumPlugin | ( | ) |
Constructor.
Definition at line 34 of file pendulum_plugin.cpp.
|
virtual |
Destructor.
Definition at line 46 of file pendulum_plugin.cpp.
|
virtual |
The Load function is called by Gazebo when the plugin is inserted into simulation.
[in] | _model | A pointer to the model that the plugin is attached to. |
[in] | _sdf | A pointer to the plugin's SDF element. |
Definition at line 56 of file pendulum_plugin.cpp.
double gazebo::PendulumPlugin::GetJointForce | ( | ) |
Get currently applied force at the joint.
Definition at line 81 of file pendulum_plugin.cpp.
void gazebo::PendulumPlugin::SetJointForce | ( | const double & | _force | ) |
Apply force at a specific joint.
[in] | _force | Force to apply |
Definition at line 89 of file pendulum_plugin.cpp.
void gazebo::PendulumPlugin::SetJointVelocity | ( | const double & | _vel | ) |
Set the velocity of the joint.
[in] | _vel | New target velocity |
Definition at line 106 of file pendulum_plugin.cpp.
void gazebo::PendulumPlugin::SetJointPosition | ( | const double & | _pos | ) |
Set the position of the joint.
[in] | _pos | New target position in radians |
Definition at line 123 of file pendulum_plugin.cpp.
void gazebo::PendulumPlugin::OnJointStateMsg | ( | const sensor_msgs::JointStateConstPtr & | _msg | ) |
The OnJointStateMsg function handles an incoming joint state message from ROS.
[in] | _msg | A message holding data to describe the state of a set of controlled joints. The state is defined by
|
Definition at line 139 of file pendulum_plugin.cpp.
void gazebo::PendulumPlugin::ProcessQueueThread | ( | ) |
The ProcessQueueThread function is a ROS helper function that processes messages.
Definition at line 158 of file pendulum_plugin.cpp.
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.
|
protected |
The initRos function is called to initialize ROS.
Definition at line 183 of file pendulum_plugin.cpp.
|
protected |
The InitRosQueueThreads function is called to initialize the ROS Publish and Process Queue Threads.
Definition at line 224 of file pendulum_plugin.cpp.
|
protected |
The InitJointControllers function is called to setup joint PID controllers.
Definition at line 236 of file pendulum_plugin.cpp.
|
protected |
The InitJointConfiguration function is called to initialize the desired joint configuration.
Definition at line 250 of file pendulum_plugin.cpp.
|
private |
Pointer to the model.
Definition at line 130 of file pendulum_plugin.h.
|
private |
Model name.
Definition at line 133 of file pendulum_plugin.h.
|
private |
Pointers to the joint.
Definition at line 136 of file pendulum_plugin.h.
|
private |
Velocity P-gain.
Definition at line 139 of file pendulum_plugin.h.
|
private |
Velocity I-gain.
Definition at line 142 of file pendulum_plugin.h.
|
private |
Velocity D-gain.
Definition at line 145 of file pendulum_plugin.h.
|
private |
Position P-gain.
Definition at line 148 of file pendulum_plugin.h.
|
private |
Position I-gain.
Definition at line 151 of file pendulum_plugin.h.
|
private |
Position D-gain.
Definition at line 154 of file pendulum_plugin.h.
|
private |
Control mode indicator { position = 1, velocity = 2, torque = 3 }.
Definition at line 158 of file pendulum_plugin.h.
|
private |
Node used for ROS transport.
Definition at line 161 of file pendulum_plugin.h.
|
private |
ROS Joint State Subscriber.
Definition at line 164 of file pendulum_plugin.h.
|
private |
ROS Joint Force (Torque) Publisher.
Definition at line 167 of file pendulum_plugin.h.
|
private |
ROS callbackque that helps process messages.
Definition at line 170 of file pendulum_plugin.h.
|
private |
ROS callbackque that helps publish messages.
Definition at line 173 of file pendulum_plugin.h.
|
private |
Thread running the rosProcessQueue.
Definition at line 176 of file pendulum_plugin.h.
|
private |
Thread running the rosPublishQueue.
Definition at line 179 of file pendulum_plugin.h.