22 #ifndef SERVO_PLUGIN_H 23 #define SERVO_PLUGIN_H 25 #include <gazebo/common/Plugin.hh> 26 #include <gazebo/common/Time.hh> 27 #if (GAZEBO_MAJOR_VERSION < 8) 28 #include <gazebo/math/Quaternion.hh> 35 #include <geometry_msgs/QuaternionStamped.h> 36 #include <sensor_msgs/JointState.h> 39 #include <boost/thread.hpp> 40 #include <boost/bind.hpp> 53 virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
73 #if (GAZEBO_MAJOR_VERSION >= 8) 74 ignition::math::Vector3d
axis;
111 void cmdCallback(
const geometry_msgs::QuaternionStamped::ConstPtr& cmd_msg);
115 #if (GAZEBO_MAJOR_VERSION >= 8)
void CalculateVelocities()
common::Time prevUpdateTime
unsigned int countOfServos
event::ConnectionPtr updateConnection
ros::Publisher jointStatePub_
tf::TransformListener * transform_listener_
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
math::Quaternion rotation_
void publish_joint_states()
float proportionalControllerGain
unsigned int orderOfAxes[3]
ros::CallbackQueue queue_
void cmdCallback(const geometry_msgs::QuaternionStamped::ConstPtr &cmd_msg)
physics::WorldPtr world
The parent World.
unsigned int rotationConv
common::Time controlPeriod
std::string jointStateName
geometry_msgs::QuaternionStamped::ConstPtr current_cmd
std::string robotNamespace
float derivativeControllerGain
ros::NodeHandle * rosnode_
struct gazebo::ServoPlugin::Servo servo[3]
sensor_msgs::JointState joint_state