30 #include <gazebo/gazebo.hh>
31 #include <gazebo/physics/physics.hh>
32 #include <gazebo/transport/transport.hh>
33 #include <gazebo/msgs/msgs.hh>
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"
79 public:
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
104 public:
void OnJointStateMsg(
const sensor_msgs::JointStateConstPtr &_msg);
161 private: std::unique_ptr<ros::NodeHandle>
rosNode;
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.